diff --git a/Jenkinsfile b/Jenkinsfile index 20bfcccf6..f6d07bc85 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -49,7 +49,6 @@ def phone_steps(String device_type, steps) { pipeline { agent none environment { - COMMA_JWT = credentials('athena-test-jwt') TEST_DIR = "/data/openpilot" SOURCE_DIR = "/data/openpilot_source/" } diff --git a/README.md b/README.md index 01c4dd0ae..83e6c7d30 100644 --- a/README.md +++ b/README.md @@ -67,8 +67,8 @@ Supported Cars | Acura | ILX 2016-19 | AcuraWatch Plus | openpilot | 25mph1 | 25mph | | Acura | RDX 2016-18 | AcuraWatch Plus | openpilot | 25mph1 | 12mph | | Acura | RDX 2019-21 | All | Stock | 0mph | 3mph | -| Honda | Accord 2018-20 | All | Stock | 0mph | 3mph | -| Honda | Accord Hybrid 2018-20 | All | Stock | 0mph | 3mph | +| Honda | Accord 2018-21 | All | Stock | 0mph | 3mph | +| Honda | Accord Hybrid 2018-21 | All | Stock | 0mph | 3mph | | Honda | Civic Hatchback 2017-21 | Honda Sensing | Stock | 0mph | 12mph | | Honda | Civic Coupe 2016-18 | Honda Sensing | openpilot | 0mph | 12mph | | Honda | Civic Coupe 2019-20 | All | Stock | 0mph | 2mph2 | @@ -110,7 +110,7 @@ Supported Cars | Toyota | C-HR 2017-20 | All | Stock | 0mph | 0mph | | Toyota | C-HR Hybrid 2017-19 | All | Stock | 0mph | 0mph | | Toyota | Corolla 2017-19 | All | Stock3| 20mph1 | 0mph | -| Toyota | Corolla 2020-21 | All | openpilot | 0mph | 0mph | +| Toyota | Corolla 2020-22 | All | openpilot | 0mph | 0mph | | Toyota | Corolla Hatchback 2019-21 | All | openpilot | 0mph | 0mph | | Toyota | Corolla Hybrid 2020-21 | All | openpilot | 0mph | 0mph | | Toyota | Highlander 2017-19 | All | Stock3| 0mph | 0mph | @@ -163,13 +163,16 @@ Community Maintained Cars and Features | Hyundai | Ioniq PHEV 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Kona Hybrid 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph | | Hyundai | Sonata 2018-2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Sonata Hybrid 2021 | All | Stock | 0mph | 0mph | | Hyundai | Veloster 2019-20 | SCC + LKAS | Stock | 5mph | 0mph | | Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | | Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | | Kia | Forte 2018-2021 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Niro EV 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Niro Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph | | Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph | | Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | @@ -177,6 +180,7 @@ Community Maintained Cars and Features | Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | | Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Telluride 2020 | SCC + LKAS | Stock | 0mph | 0mph | | Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Leaf 2018-20 | ProPILOT | Stock | 0mph | 0mph | | Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | @@ -184,7 +188,7 @@ Community Maintained Cars and Features | SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | | SEAT | Leon 2014-2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Octavia 2015, 2019 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia 2015, 2018-19 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Octavia RS 2016 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | | Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | diff --git a/RELEASES.md b/RELEASES.md index aa7823c5e..a52ad3760 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,19 @@ +Version 0.8.8 (2021-08-27) +======================== + * New driving model with improved laneless performance + * Trained on 5000+ hours of diverse driving data from 3000+ users in 40+ countries + * Better anti-cheating methods during simulator training ensure the model hugs less when in laneless mode + * All new desire ground-truthing stack makes the model better at lane changes + * New driver monitoring model: improved performance on comma three + * NEOS 18 for comma two: update packages + * AGNOS 1.3 for comma three: fix display init at high temperatures + * Improved auto-exposure on comma three + * Honda Accord 2021 support thanks to csouers! + * Honda Accord Hybrid 2021 support thanks to csouers! + * Hyundai Kona Hybrid 2020 support thanks to haram-KONA! + * Hyundai Sonata Hybrid 2021 support thanks to Matt-Wash-Burn! + * Kia Niro Hybrid 2021 support thanks to tetious! + Version 0.8.7 (2021-07-31) ======================== * comma three support! diff --git a/SAFETY.md b/SAFETY.md index 8b4f33500..d36d53437 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -15,7 +15,7 @@ used safely** and openpilot is provided with no warranty of fitness for any purp openpilot is developed in good faith to be compliant with FMVSS requirements and to follow industry standards of safety for Level 2 Driver Assistance Systems. In particular, we observe ISO26262 guidelines, including those from [pertinent documents](https://www.nhtsa.gov/sites/nhtsa.dot.gov/files/documents/13498a_812_573_alcsystemreport.pdf) -released by NHTSA. In addition, we impose strict coding guidelines (like [MISRA C : 2012](https://www.misra.org.uk/MISRAHome/MISRAC2012/tabid/196/Default.aspx)) +released by NHTSA. In addition, we impose strict coding guidelines (like [MISRA C : 2012](https://www.misra.org.uk/what-is-misra/)) on parts of openpilot that are safety relevant. We also perform software-in-the-loop, hardware-in-the-loop and in-vehicle tests before each software release. diff --git a/SConstruct b/SConstruct index d5f46f8d9..02a93eb98 100644 --- a/SConstruct +++ b/SConstruct @@ -166,6 +166,10 @@ else: if arch != "Darwin": ldflags += ["-Wl,--as-needed"] +# Enable swaglog include in submodules +cflags += ["-DSWAGLOG"] +cxxflags += ["-DSWAGLOG"] + # change pythonpath to this lenv["PYTHONPATH"] = Dir("#").path @@ -344,6 +348,17 @@ if GetOption("clazy"): Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM') +SConscript(['selfdrive/common/SConscript']) +Import('_common', '_gpucommon', '_gpu_libs') + +if SHARED: + common, gpucommon = abspath(common), abspath(gpucommon) +else: + common = [_common, 'json11'] + gpucommon = [_gpucommon] + _gpu_libs + +Export('common', 'gpucommon') + # cereal and messaging are shared with the system SConscript(['cereal/SConscript']) if SHARED: @@ -354,18 +369,7 @@ else: messaging = [File('#cereal/libmessaging.a')] visionipc = [File('#cereal/libvisionipc.a')] -Export('cereal', 'messaging') - -SConscript(['selfdrive/common/SConscript']) -Import('_common', '_gpucommon', '_gpu_libs') - -if SHARED: - common, gpucommon = abspath(common), abspath(gpucommon) -else: - common = [_common, 'json11'] - gpucommon = [_gpucommon] + _gpu_libs - -Export('common', 'gpucommon', 'visionipc') +Export('cereal', 'messaging', 'visionipc') # Build rednose library and ekf models diff --git a/cereal/SConscript b/cereal/SConscript index b3c8da9ae..10f3ab7f5 100644 --- a/cereal/SConscript +++ b/cereal/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch') +Import('env', 'envCython', 'arch', 'common') import shutil @@ -40,10 +40,10 @@ messaging_objects = env.SharedObject([ messaging_lib = env.Library('messaging', messaging_objects) Depends('messaging/impl_zmq.cc', services_h) -env.Program('messaging/bridge', ['messaging/bridge.cc'], LIBS=[messaging_lib, 'zmq']) +env.Program('messaging/bridge', ['messaging/bridge.cc'], LIBS=[messaging_lib, 'zmq', common]) Depends('messaging/bridge.cc', services_h) -envCython.Program('messaging/messaging_pyx.so', 'messaging/messaging_pyx.pyx', LIBS=envCython["LIBS"]+[messaging_lib, "zmq"]) +envCython.Program('messaging/messaging_pyx.so', 'messaging/messaging_pyx.pyx', LIBS=envCython["LIBS"]+[messaging_lib, "zmq", common]) # Build Vision IPC @@ -63,7 +63,7 @@ vipc_objects = env.SharedObject(vipc_sources) vipc = env.Library('visionipc', vipc_objects) -libs = envCython["LIBS"]+["OpenCL", "zmq", vipc, messaging_lib] +libs = envCython["LIBS"]+["OpenCL", "zmq", vipc, messaging_lib, common] if arch == "aarch64": libs += ["adreno_utils"] if arch == "Darwin": @@ -73,5 +73,5 @@ envCython.Program('visionipc/visionipc_pyx.so', 'visionipc/visionipc_pyx.pyx', L if GetOption('test'): - env.Program('messaging/test_runner', ['messaging/test_runner.cc', 'messaging/msgq_tests.cc'], LIBS=[messaging_lib]) - env.Program('visionipc/test_runner', ['visionipc/test_runner.cc', 'visionipc/visionipc_tests.cc'], LIBS=[vipc, messaging_lib, 'zmq', 'pthread', 'OpenCL']) + env.Program('messaging/test_runner', ['messaging/test_runner.cc', 'messaging/msgq_tests.cc'], LIBS=[messaging_lib, common]) + env.Program('visionipc/test_runner', ['visionipc/test_runner.cc', 'visionipc/visionipc_tests.cc'], LIBS=[vipc, messaging_lib, 'zmq', 'pthread', 'OpenCL', common]) diff --git a/cereal/car.capnp b/cereal/car.capnp index 922209433..15fa48916 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -108,6 +108,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { driverCameraError @101; wideRoadCameraError @102; localizerMalfunction @103; + highCpuUsage @105; driverMonitorLowAccDEPRECATED @68; radarCanErrorDEPRECATED @15; @@ -156,6 +157,7 @@ struct CarState { # 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 @@ -302,6 +304,7 @@ struct CarControl { # range from -1.0 - 1.0 steer @2: Float32; steeringAngleDeg @3: Float32; + accel @4: Float32; # m/s^2 } struct CruiseControl { diff --git a/cereal/log.capnp b/cereal/log.capnp index 79c1fd9b2..854a75694 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -289,15 +289,11 @@ struct CanData { } struct DeviceState @0xa4d8b5af2aa492eb { - freeSpacePercent @7 :Float32; - memoryUsagePercent @19 :Int8; - cpuUsagePercent @20 :Int8; - gpuUsagePercent @33 :Int8; usbOnline @12 :Bool; networkType @22 :NetworkType; networkInfo @31 :NetworkInfo; - offroadPowerUsageUwh @23 :UInt32; networkStrength @24 :NetworkStrength; + offroadPowerUsageUwh @23 :UInt32; carBatteryCapacityUwh @25 :UInt32; fanSpeedPercentDesired @10 :UInt16; @@ -306,6 +302,12 @@ struct DeviceState @0xa4d8b5af2aa492eb { lastAthenaPingTime @32 :UInt64; + # system utilization + freeSpacePercent @7 :Float32; + memoryUsagePercent @19 :Int8; + gpuUsagePercent @33 :Int8; + cpuUsagePercent @34 :List(Int8); # per-core cpu usage + # power batteryPercent @8 :Int16; batteryStatus @9 :Text; @@ -365,6 +367,7 @@ struct DeviceState @0xa4d8b5af2aa492eb { gpuDEPRECATED @5 :UInt16; batDEPRECATED @6 :UInt32; pa0DEPRECATED @21 :UInt16; + cpuUsagePercentDEPRECATED @20 :Int8; } struct PandaState @0xa7649e2575e4591e { @@ -432,7 +435,7 @@ struct PandaState @0xa7649e2575e4591e { pedal @4; uno @5; dos @6; - red @7; + redPanda @7; } enum UsbPowerMode { @@ -934,7 +937,7 @@ struct LiveLocationKalman { angularVelocityDevice @8 : Measurement; # orientationNEDCalibrated transforms to rot matrix: NED_from_calibrated - orientationNEDCalibrated @9 : Measurement; + calibratedOrientationNED @9 : Measurement; # Calibrated frame is simply device frame # aligned with the vehicle diff --git a/cereal/logger/logger.h b/cereal/logger/logger.h new file mode 100644 index 000000000..e21509352 --- /dev/null +++ b/cereal/logger/logger.h @@ -0,0 +1,20 @@ +#pragma once + +#ifdef SWAGLOG +#include "selfdrive/common/swaglog.h" +#else + +#define CLOUDLOG_DEBUG 10 +#define CLOUDLOG_INFO 20 +#define CLOUDLOG_WARNING 30 +#define CLOUDLOG_ERROR 40 +#define CLOUDLOG_CRITICAL 50 + +#define cloudlog(lvl, fmt, ...) printf(fmt "\n", ## __VA_ARGS__) + +#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#endif diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 1628dd524..0440104eb 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -13,6 +13,7 @@ from cereal.services import service_list assert MultiplePublishersError assert MessagingError +NO_TRAVERSAL_LIMIT = 2**64-1 AVG_FREQ_HISTORY = 100 SIMULATION = "SIMULATION" in os.environ @@ -26,6 +27,9 @@ except ImportError: context = Context() +def log_from_bytes(dat: bytes) -> capnp.lib.capnp._DynamicStructReader: + return log.Event.from_bytes(dat, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) + def new_message(service: Optional[str] = None, size: Optional[int] = None) -> capnp.lib.capnp._DynamicStructBuilder: dat = log.Event.new_message() dat.logMonoTime = int(sec_since_boot() * 1e9) @@ -83,7 +87,7 @@ def drain_sock(sock: SubSocket, wait_for_one: bool = False) -> List[capnp.lib.ca if dat is None: # Timeout hit break - dat = log.Event.from_bytes(dat) + dat = log_from_bytes(dat) ret.append(dat) return ret @@ -106,20 +110,20 @@ def recv_sock(sock: SubSocket, wait: bool = False) -> Union[None, capnp.lib.capn dat = rcv if dat is not None: - dat = log.Event.from_bytes(dat) + dat = log_from_bytes(dat) return dat def recv_one(sock: SubSocket) -> Union[None, capnp.lib.capnp._DynamicStructReader]: dat = sock.receive() if dat is not None: - dat = log.Event.from_bytes(dat) + dat = log_from_bytes(dat) return dat def recv_one_or_none(sock: SubSocket) -> Union[None, capnp.lib.capnp._DynamicStructReader]: dat = sock.receive(non_blocking=True) if dat is not None: - dat = log.Event.from_bytes(dat) + dat = log_from_bytes(dat) return dat def recv_one_retry(sock: SubSocket) -> capnp.lib.capnp._DynamicStructReader: @@ -127,7 +131,7 @@ def recv_one_retry(sock: SubSocket) -> capnp.lib.capnp._DynamicStructReader: while True: dat = sock.receive() if dat is not None: - return log.Event.from_bytes(dat) + return log_from_bytes(dat) class SubMaster(): def __init__(self, services: List[str], poll: Optional[List[str]] = None, diff --git a/cereal/messaging/messaging.h b/cereal/messaging/messaging.h index 8c0825bb2..4a184ff70 100644 --- a/cereal/messaging/messaging.h +++ b/cereal/messaging/messaging.h @@ -69,7 +69,7 @@ public: SubMaster(const std::vector &service_list, const char *address = nullptr, const std::vector &ignore_alive = {}); void update(int timeout = 1000); - void update_msgs(uint64_t current_time, std::vector> messages); + void update_msgs(uint64_t current_time, const std::vector> &messages); inline bool allAlive(const std::vector &service_list = {}) { return all_(service_list, false, true); } inline bool allValid(const std::vector &service_list = {}) { return all_(service_list, true, false); } inline bool allAliveAndValid(const std::vector &service_list = {}) { return all_(service_list, true, true); } diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc index c88a033bf..56698dc2e 100644 --- a/cereal/messaging/socketmaster.cc +++ b/cereal/messaging/socketmaster.cc @@ -92,7 +92,9 @@ void SubMaster::update(int timeout) { SubMessage *m = messages_.at(s); m->msg_reader->~FlatArrayMessageReader(); - m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader(m->aligned_buf.align(msg)); + capnp::ReaderOptions options; + options.traversalLimitInWords = kj::maxValue; // Don't limit + m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader(m->aligned_buf.align(msg), options); delete msg; messages.push_back({m->name, m->msg_reader->getRoot()}); } @@ -100,7 +102,7 @@ void SubMaster::update(int timeout) { update_msgs(current_time, messages); } -void SubMaster::update_msgs(uint64_t current_time, std::vector> messages){ +void SubMaster::update_msgs(uint64_t current_time, const std::vector> &messages){ if (++frame == UINT64_MAX) frame = 1; for(auto &kv : messages) { diff --git a/cereal/services.py b/cereal/services.py index 9acdaefc1..406d9d146 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -61,6 +61,9 @@ services = { "modelV2": (True, 20., 40), "managerState": (True, 2., 1), "uploaderState": (True, 0., 1), + + # debug + "testJoystick": (False, 0.), } service_list = {name: Service(new_port(idx), *vals) for # type: ignore idx, (name, vals) in enumerate(services.items())} diff --git a/cereal/visionipc/visionbuf.h b/cereal/visionipc/visionbuf.h index fad60f7ab..165a3dbdd 100644 --- a/cereal/visionipc/visionbuf.h +++ b/cereal/visionipc/visionbuf.h @@ -55,8 +55,8 @@ class VisionBuf { 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); - void sync(int dir); - void free(); + int sync(int dir); + int free(); }; void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h); diff --git a/cereal/visionipc/visionbuf_cl.cc b/cereal/visionipc/visionbuf_cl.cc index 6fb2884b5..2dd9068d8 100644 --- a/cereal/visionipc/visionbuf_cl.cc +++ b/cereal/visionipc/visionbuf_cl.cc @@ -60,27 +60,36 @@ void VisionBuf::import(){ } -void VisionBuf::sync(int dir) { +int VisionBuf::sync(int dir) { int err = 0; - if (!this->buf_cl) return; + if (!this->buf_cl) return 0; if (dir == VISIONBUF_SYNC_FROM_DEVICE) { err = clEnqueueReadBuffer(this->copy_q, this->buf_cl, CL_FALSE, 0, this->len, this->addr, 0, NULL, NULL); } else { err = clEnqueueWriteBuffer(this->copy_q, this->buf_cl, CL_FALSE, 0, this->len, this->addr, 0, NULL, NULL); } - assert(err == 0); - clFinish(this->copy_q); -} -void VisionBuf::free() { - if (this->buf_cl){ - int err = clReleaseMemObject(this->buf_cl); - assert(err == 0); - - clReleaseCommandQueue(this->copy_q); + if (err == 0){ + err = clFinish(this->copy_q); } - munmap(this->addr, this->len); - close(this->fd); + return err; +} + +int VisionBuf::free() { + int err = 0; + if (this->buf_cl){ + err = clReleaseMemObject(this->buf_cl); + if (err != 0) return err; + + err = clReleaseCommandQueue(this->copy_q); + if (err != 0) return err; + } + + err = munmap(this->addr, this->len); + if (err != 0) return err; + + err = close(this->fd); + return err; } diff --git a/cereal/visionipc/visionbuf_ion.cc b/cereal/visionipc/visionbuf_ion.cc index 92b72b04d..60f7c66e1 100644 --- a/cereal/visionipc/visionbuf_ion.cc +++ b/cereal/visionipc/visionbuf_ion.cc @@ -104,9 +104,7 @@ void VisionBuf::init_cl(cl_device_id device_id, cl_context ctx) { } -void VisionBuf::sync(int dir) { - int err; - +int VisionBuf::sync(int dir) { struct ion_flush_data flush_data = {0}; flush_data.handle = this->handle; flush_data.vaddr = this->addr; @@ -124,19 +122,23 @@ void VisionBuf::sync(int dir) { ION_IOC_INV_CACHES : ION_IOC_CLEAN_CACHES; custom_data.arg = (unsigned long)&flush_data; - err = ioctl(ion_fd, ION_IOC_CUSTOM, &custom_data); - assert(err == 0); + return ioctl(ion_fd, ION_IOC_CUSTOM, &custom_data); } -void VisionBuf::free() { +int VisionBuf::free() { + int err = 0; + if (this->buf_cl){ - int err = clReleaseMemObject(this->buf_cl); - assert(err == 0); + err = clReleaseMemObject(this->buf_cl); + if (err != 0) return err; } - munmap(this->addr, this->mmap_len); - close(this->fd); + err = munmap(this->addr, this->mmap_len); + if (err != 0) return err; + + err = close(this->fd); + if (err != 0) return err; struct ion_handle_data handle_data = {.handle = this->handle}; - ioctl(ion_fd, ION_IOC_FREE, &handle_data); + return ioctl(ion_fd, ION_IOC_FREE, &handle_data); } diff --git a/cereal/visionipc/visionipc_client.cc b/cereal/visionipc/visionipc_client.cc index d46cc0e4a..69ae8b133 100644 --- a/cereal/visionipc/visionipc_client.cc +++ b/cereal/visionipc/visionipc_client.cc @@ -3,9 +3,10 @@ #include #include -#include "ipc.h" -#include "visionipc_client.h" -#include "visionipc_server.h" +#include "visionipc/ipc.h" +#include "visionipc/visionipc_client.h" +#include "visionipc/visionipc_server.h" +#include "logger/logger.h" VisionIpcClient::VisionIpcClient(std::string name, VisionStreamType type, bool conflate, cl_device_id device_id, cl_context ctx) : name(name), type(type), device_id(device_id), ctx(ctx) { msg_ctx = Context::create(); @@ -21,8 +22,11 @@ bool VisionIpcClient::connect(bool blocking){ // Cleanup old buffers on reconnect for (size_t i = 0; i < num_buffers; i++){ - buffers[i].free(); + if (buffers[i].free() != 0) { + LOGE("Failed to free buffer %zu", i); + } } + num_buffers = 0; // Connect to server socket and ask for all FDs of type @@ -101,7 +105,10 @@ VisionBuf * VisionIpcClient::recv(VisionIpcBufExtra * extra, const int timeout_m *extra = packet->extra; } - buf->sync(VISIONBUF_SYNC_TO_DEVICE); + if (buf->sync(VISIONBUF_SYNC_TO_DEVICE) != 0) { + LOGE("Failed to sync buffer"); + } + delete r; return buf; } @@ -110,7 +117,9 @@ VisionBuf * VisionIpcClient::recv(VisionIpcBufExtra * extra, const int timeout_m VisionIpcClient::~VisionIpcClient(){ for (size_t i = 0; i < num_buffers; i++){ - buffers[i].free(); + if (buffers[i].free() != 0) { + LOGE("Failed to free buffer %zu", i); + } } delete sock; diff --git a/cereal/visionipc/visionipc_server.cc b/cereal/visionipc/visionipc_server.cc index adfc23190..fdacd7843 100644 --- a/cereal/visionipc/visionipc_server.cc +++ b/cereal/visionipc/visionipc_server.cc @@ -10,6 +10,7 @@ #include "messaging/messaging.h" #include "visionipc/ipc.h" #include "visionipc/visionipc_server.h" +#include "logger/logger.h" std::string get_endpoint_name(std::string name, VisionStreamType type){ if (messaging_use_zmq()){ @@ -145,7 +146,11 @@ VisionBuf * VisionIpcServer::get_buffer(VisionStreamType type){ } void VisionIpcServer::send(VisionBuf * buf, VisionIpcBufExtra * extra, bool sync){ - if (sync) buf->sync(VISIONBUF_SYNC_FROM_DEVICE); + if (sync) { + if (buf->sync(VISIONBUF_SYNC_FROM_DEVICE) != 0) { + LOGE("Failed to sync buffer"); + } + } assert(buffers.count(buf->type)); assert(buf->idx < buffers[buf->type].size()); @@ -165,7 +170,9 @@ VisionIpcServer::~VisionIpcServer(){ // VisionBuf cleanup for( auto const& [type, buf] : buffers ) { for (VisionBuf* b : buf){ - b->free(); + if (b->free() != 0) { + LOGE("Failed to free buffer"); + } delete b; } } diff --git a/common/api/__init__.py b/common/api/__init__.py index 365e4f5ea..5b1d66cf7 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -1,9 +1,12 @@ import jwt +import os import requests from datetime import datetime, timedelta from common.basedir import PERSIST from selfdrive.version import version +API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') + class Api(): def __init__(self, dongle_id): self.dongle_id = dongle_id @@ -34,12 +37,10 @@ class Api(): def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): - backend = "https://api.commadotai.com/" - headers = {} if access_token is not None: headers['Authorization'] = "JWT "+access_token headers['User-Agent'] = "openpilot-" + version - return requests.request(method, backend+endpoint, timeout=timeout, headers=headers, params=params) + return requests.request(method, API_HOST + "/" + endpoint, timeout=timeout, headers=headers, params=params) diff --git a/common/file_helpers.py b/common/file_helpers.py index c7a70ab87..a344a71fe 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -79,6 +79,25 @@ class NamedTemporaryDir(): self.close() +class CallbackReader: + """Wraps a file, but overrides the read method to also + call a callback function with the number of bytes read so far.""" + def __init__(self, f, callback, *args): + self.f = f + self.callback = callback + self.cb_args = args + self.total_read = 0 + + def __getattr__(self, attr): + return getattr(self.f, attr) + + def read(self, *args, **kwargs): + chunk = self.f.read(*args, **kwargs) + self.total_read += len(chunk) + self.callback(*self.cb_args, self.total_read) + return chunk + + def _get_fileobject_func(writer, temp_dir): def _get_fileobject(): file_obj = writer.get_fileobject(dir=temp_dir) diff --git a/common/filter_simple.py b/common/filter_simple.py index fa291bcb6..f44bc9eae 100644 --- a/common/filter_simple.py +++ b/common/filter_simple.py @@ -1,9 +1,13 @@ -class FirstOrderFilter(): +class FirstOrderFilter: # first order filter - def __init__(self, x0, ts, dt): - self.k = (dt / ts) / (1. + dt / ts) + def __init__(self, x0, rc, dt): self.x = x0 + self.dt = dt + self.update_alpha(rc) + + def update_alpha(self, rc): + self.alpha = self.dt / (rc + self.dt) def update(self, x): - self.x = (1. - self.k) * self.x + self.k * x + self.x = (1. - self.alpha) * self.x + self.alpha * x return self.x diff --git a/common/params_pxd.pxd b/common/params_pxd.pxd index 489e064dc..ecf520041 100644 --- a/common/params_pxd.pxd +++ b/common/params_pxd.pxd @@ -17,7 +17,7 @@ cdef extern from "selfdrive/common/params.h": ALL cdef cppclass Params: - Params(bool) nogil + Params() nogil Params(string) nogil string get(string, bool) nogil bool getBool(string) nogil diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 4a238a7d4..198c69068 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -30,11 +30,11 @@ class UnknownKeyName(Exception): cdef class Params: cdef c_Params* p - def __cinit__(self, d=None, bool persistent_params=False): + def __cinit__(self, d=None): cdef string path if d is None: with nogil: - self.p = new c_Params(persistent_params) + self.p = new c_Params() else: path = d.encode() with nogil: diff --git a/installer/continue_openpilot.sh b/installer/continue_openpilot.sh deleted file mode 100755 index 3da67313e..000000000 --- a/installer/continue_openpilot.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/usr/bin/bash - -cd /data/openpilot -exec ./launch_openpilot.sh diff --git a/installer/updater/update.json b/installer/updater/update.json index 465320544..228029e9f 100644 --- a/installer/updater/update.json +++ b/installer/updater/update.json @@ -1,7 +1,7 @@ { - "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266.zip", - "ota_hash": "c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266", - "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5.img", - "recovery_len": 15209772, - "recovery_hash": "c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5" + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-5dc2575d713977666a8e14ae1b43a04d7f63123934c80fa10751d949a107653e.zip", + "ota_hash": "5dc2575d713977666a8e14ae1b43a04d7f63123934c80fa10751d949a107653e", + "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-f01a55c9ba52ca57668d1684c6bf4118efd31916b04f8c1fcd8495013d3677eb.img", + "recovery_len": 15222060, + "recovery_hash": "f01a55c9ba52ca57668d1684c6bf4118efd31916b04f8c1fcd8495013d3677eb" } diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index d8bf6da5c..92f318952 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -10,11 +10,21 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" function two_init { - # Wifi scan - wpa_cli IFNAME=wlan0 SCAN + # set IO scheduler + setprop sys.io.scheduler noop + for f in /sys/block/*/queue/scheduler; do + echo noop > $f + done # *** shield cores 2-3 *** + # TODO: should we enable this? + # offline cores 2-3 to force recurring timers onto the other cores + #echo 0 > /sys/devices/system/cpu/cpu2/online + #echo 0 > /sys/devices/system/cpu/cpu3/online + #echo 1 > /sys/devices/system/cpu/cpu2/online + #echo 1 > /sys/devices/system/cpu/cpu3/online + # android gets two cores echo 0-1 > /dev/cpuset/background/cpus echo 0-1 > /dev/cpuset/system-background/cpus @@ -75,6 +85,9 @@ function two_init { # disable bluetooth service call bluetooth_manager 8 + # wifi scan + wpa_cli IFNAME=wlan0 SCAN + # Check for NEOS update if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then if [ -f "$DIR/scripts/continue.sh" ]; then diff --git a/launch_env.sh b/launch_env.sh index 3f7b02f36..f6f3b9f17 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,11 +7,11 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$REQUIRED_NEOS_VERSION" ]; then - export REQUIRED_NEOS_VERSION="17" + export REQUIRED_NEOS_VERSION="18" fi if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="1.2" + export AGNOS_VERSION="1.3" fi if [ -z "$PASSIVE" ]; then diff --git a/models/dmonitoring_model_q.dlc b/models/dmonitoring_model_q.dlc index b067c3e6d..941020e28 100644 Binary files a/models/dmonitoring_model_q.dlc and b/models/dmonitoring_model_q.dlc differ diff --git a/models/supercombo.dlc b/models/supercombo.dlc index cbd090665..2641f23e4 100644 Binary files a/models/supercombo.dlc and b/models/supercombo.dlc differ diff --git a/panda/VERSION b/panda/VERSION deleted file mode 100644 index ad90322ab..000000000 --- a/panda/VERSION +++ /dev/null @@ -1 +0,0 @@ -v1.7.5 \ No newline at end of file diff --git a/panda/__init__.py b/panda/__init__.py index 98ed364e7..81ee2f013 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -1,3 +1,9 @@ # flake8: noqa # pylint: skip-file -from .python import Panda, PandaWifiStreaming, PandaDFU, flash_release, BASEDIR, ensure_st_up_to_date, PandaSerial +from .python import Panda, PandaWifiStreaming, PandaDFU, flash_release, \ + BASEDIR, ensure_st_up_to_date, PandaSerial, \ + DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, MCU_TYPE_F4 + +from .python.config import BOOTSTUB_ADDRESS, BLOCK_SIZE_FX, APP_ADDRESS_FX, \ + BLOCK_SIZE_H7, APP_ADDRESS_H7, DEVICE_SERIAL_NUMBER_ADDR_H7, \ + DEVICE_SERIAL_NUMBER_ADDR_FX diff --git a/panda/board/SConscript b/panda/board/SConscript index 02e582463..c16d191bd 100644 --- a/panda/board/SConscript +++ b/panda/board/SConscript @@ -8,6 +8,7 @@ if os.getenv("PEDAL"): PROJECT = "pedal" STARTUP_FILE = "stm32fx/startup_stm32f205xx.s" LINKER_SCRIPT = "stm32fx/stm32fx_flash.ld" + APP_START_ADDRESS = "0x8004000" MAIN = "pedal/main.c" PROJECT_FLAGS = [ "-mcpu=cortex-m3", @@ -18,12 +19,32 @@ if os.getenv("PEDAL"): "-DPEDAL", ] if os.getenv("PEDAL_USB"): + PROJECT = "pedal_usb" PROJECT_FLAGS.append("-DPEDAL_USB") +elif os.getenv("PANDA_H7"): + PROJECT = "panda_h7" + STARTUP_FILE = "stm32h7/startup_stm32h7x5xx.s" + LINKER_SCRIPT = "stm32h7/stm32h7x5_flash.ld" + APP_START_ADDRESS = "0x8020000" + MAIN = "main.c" + PROJECT_FLAGS = [ + "-mcpu=cortex-m7", + "-mhard-float", + "-DSTM32H7", + "-DSTM32H725xx", + "-mfpu=fpv5-d16", + "-fsingle-precision-constant", + "-Os", + "-g", + "-DPANDA", + ] + else: PROJECT = "panda" STARTUP_FILE = "stm32fx/startup_stm32f413xx.s" LINKER_SCRIPT = "stm32fx/stm32fx_flash.ld" + APP_START_ADDRESS = "0x8004000" MAIN = "main.c" PROJECT_FLAGS = [ "-mcpu=cortex-m4", @@ -39,13 +60,11 @@ else: def get_version(builder, build_type): - version_file = File('../VERSION').srcnode().abspath - version = open(version_file).read() try: git = subprocess.check_output(["git", "rev-parse", "--short=8", "HEAD"], encoding='utf8').strip() except subprocess.CalledProcessError: git = "unknown" - return f"{version}-{builder}-{git}-{build_type}" + return f"{builder}-{git}-{build_type}" def to_c_uint32(x): @@ -110,6 +129,7 @@ else: includes = [ "stm32fx/inc", + "stm32h7/inc", "..", ".", ] @@ -150,7 +170,7 @@ bootstub_bin = panda_env.Objcopy(f"obj/bootstub.{PROJECT}.bin", bootstub_elf) # Build main main_elf = panda_env.Program(f"obj/{PROJECT}.elf", [startup, MAIN], - LINKFLAGS=["-Wl,--section-start,.isr_vector=0x8004000"] + flags) + LINKFLAGS=[f"-Wl,--section-start,.isr_vector={APP_START_ADDRESS}"] + flags) main_bin = panda_env.Objcopy(f"obj/{PROJECT}.bin", main_elf) # Sign main diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index 9333402fa..5e86deecd 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -127,41 +127,11 @@ void black_set_can_mode(uint8_t mode){ } } -void black_usb_power_mode_tick(uint32_t uptime){ - UNUSED(uptime); - // Not applicable -} - bool black_check_ignition(void){ // ignition is checked through harness return harness_check_ignition(); } -uint32_t black_read_current(void){ - // No current sense on black panda - return 0U; -} - -void black_set_ir_power(uint8_t percentage){ - UNUSED(percentage); -} - -void black_set_fan_power(uint8_t percentage){ - UNUSED(percentage); -} - -void black_set_phone_power(bool enabled){ - UNUSED(enabled); -} - -void black_set_clock_source_mode(uint8_t mode){ - UNUSED(mode); -} - -void black_set_siren(bool enabled){ - UNUSED(enabled); -} - void black_init(void) { common_init_gpio(); @@ -244,12 +214,12 @@ const board board_black = { .set_usb_power_mode = black_set_usb_power_mode, .set_gps_mode = black_set_gps_mode, .set_can_mode = black_set_can_mode, - .usb_power_mode_tick = black_usb_power_mode_tick, + .usb_power_mode_tick = unused_usb_power_mode_tick, .check_ignition = black_check_ignition, - .read_current = black_read_current, - .set_fan_power = black_set_fan_power, - .set_ir_power = black_set_ir_power, - .set_phone_power = black_set_phone_power, - .set_clock_source_mode = black_set_clock_source_mode, - .set_siren = black_set_siren + .read_current = unused_read_current, + .set_fan_power = unused_set_fan_power, + .set_ir_power = unused_set_ir_power, + .set_phone_power = unused_set_phone_power, + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren }; diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h index 57957f760..0ec1a5f2a 100644 --- a/panda/board/boards/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -49,6 +49,7 @@ struct board { #define HW_TYPE_PEDAL 4U #define HW_TYPE_UNO 5U #define HW_TYPE_DOS 6U +#define HW_TYPE_RED_PANDA 7U // LED colors #define LED_RED 0U diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index 010aa1a4d..90f075e49 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -49,18 +49,10 @@ void dos_set_led(uint8_t color, bool enabled) { } } -void dos_set_gps_load_switch(bool enabled) { - UNUSED(enabled); -} - void dos_set_bootkick(bool enabled){ set_gpio_output(GPIOC, 4, !enabled); } -void dos_set_phone_power(bool enabled){ - UNUSED(enabled); -} - void dos_set_usb_power_mode(uint8_t mode) { bool valid = false; switch (mode) { @@ -81,10 +73,6 @@ void dos_set_usb_power_mode(uint8_t mode) { } } -void dos_set_gps_mode(uint8_t mode) { - UNUSED(mode); -} - void dos_set_can_mode(uint8_t mode){ switch (mode) { case CAN_MODE_NORMAL: @@ -113,10 +101,6 @@ void dos_set_can_mode(uint8_t mode){ } } -void dos_usb_power_mode_tick(uint32_t uptime){ - UNUSED(uptime); -} - bool dos_check_ignition(void){ // ignition is checked through harness return harness_check_ignition(); @@ -136,11 +120,6 @@ void dos_set_fan_power(uint8_t percentage){ fan_set_power(percentage); } -uint32_t dos_read_current(void){ - // No current sense on Dos - return 0U; -} - void dos_set_clock_source_mode(uint8_t mode){ clock_source_init(mode); } @@ -235,14 +214,14 @@ const board board_dos = { .enable_can_transceivers = dos_enable_can_transceivers, .set_led = dos_set_led, .set_usb_power_mode = dos_set_usb_power_mode, - .set_gps_mode = dos_set_gps_mode, + .set_gps_mode = unused_set_gps_mode, .set_can_mode = dos_set_can_mode, - .usb_power_mode_tick = dos_usb_power_mode_tick, + .usb_power_mode_tick = unused_usb_power_mode_tick, .check_ignition = dos_check_ignition, - .read_current = dos_read_current, + .read_current = unused_read_current, .set_fan_power = dos_set_fan_power, .set_ir_power = dos_set_ir_power, - .set_phone_power = dos_set_phone_power, + .set_phone_power = unused_set_phone_power, .set_clock_source_mode = dos_set_clock_source_mode, .set_siren = dos_set_siren }; diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index 3a2f3b960..ad68787fa 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -48,12 +48,12 @@ const board board_grey = { .set_usb_power_mode = white_set_usb_power_mode, .set_gps_mode = grey_set_gps_mode, .set_can_mode = white_set_can_mode, - .usb_power_mode_tick = white_usb_power_mode_tick, + .usb_power_mode_tick = unused_usb_power_mode_tick, .check_ignition = white_check_ignition, .read_current = white_read_current, - .set_fan_power = white_set_fan_power, - .set_ir_power = white_set_ir_power, - .set_phone_power = white_set_phone_power, - .set_clock_source_mode = white_set_clock_source_mode, - .set_siren = white_set_siren + .set_fan_power = unused_set_fan_power, + .set_ir_power = unused_set_ir_power, + .set_phone_power = unused_set_phone_power, + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren }; diff --git a/panda/board/boards/pedal.h b/panda/board/boards/pedal.h index bb70923b4..f3922b164 100644 --- a/panda/board/boards/pedal.h +++ b/panda/board/boards/pedal.h @@ -50,41 +50,11 @@ void pedal_set_can_mode(uint8_t mode){ } } -void pedal_usb_power_mode_tick(uint32_t uptime){ - UNUSED(uptime); - // Not applicable -} - bool pedal_check_ignition(void){ // not supported on pedal return false; } -uint32_t pedal_read_current(void){ - // No current sense on pedal - return 0U; -} - -void pedal_set_ir_power(uint8_t percentage){ - UNUSED(percentage); -} - -void pedal_set_fan_power(uint8_t percentage){ - UNUSED(percentage); -} - -void pedal_set_phone_power(bool enabled){ - UNUSED(enabled); -} - -void pedal_set_clock_source_mode(uint8_t mode){ - UNUSED(mode); -} - -void pedal_set_siren(bool enabled){ - UNUSED(enabled); -} - void pedal_init(void) { common_init_gpio(); @@ -121,12 +91,12 @@ const board board_pedal = { .set_usb_power_mode = pedal_set_usb_power_mode, .set_gps_mode = pedal_set_gps_mode, .set_can_mode = pedal_set_can_mode, - .usb_power_mode_tick = pedal_usb_power_mode_tick, + .usb_power_mode_tick = unused_usb_power_mode_tick, .check_ignition = pedal_check_ignition, - .read_current = pedal_read_current, - .set_fan_power = pedal_set_fan_power, - .set_ir_power = pedal_set_ir_power, - .set_phone_power = pedal_set_phone_power, - .set_clock_source_mode = pedal_set_clock_source_mode, - .set_siren = pedal_set_siren + .read_current = unused_read_current, + .set_fan_power = unused_set_fan_power, + .set_ir_power = unused_set_ir_power, + .set_phone_power = unused_set_phone_power, + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren }; diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h new file mode 100644 index 000000000..17d4f0392 --- /dev/null +++ b/panda/board/boards/red.h @@ -0,0 +1,202 @@ +// ///////////////////// // +// Red Panda + Harness // +// ///////////////////// // + +void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { + switch (transceiver) { + case 1U: + set_gpio_output(GPIOG, 11, !enabled); + break; + case 2U: + set_gpio_output(GPIOB, 3, !enabled); + break; + case 3U: + set_gpio_output(GPIOD, 7, !enabled); + break; + case 4U: + set_gpio_output(GPIOB, 4, !enabled); + break; + default: + break; + } +} + +void red_enable_can_transceivers(bool enabled) { + uint8_t main_bus = (car_harness_status == HARNESS_STATUS_FLIPPED) ? 3U : 1U; + for (uint8_t i=1U; i<=4U; i++) { + // Leave main CAN always on for CAN-based ignition detection + if (i == main_bus) { + red_enable_can_transceiver(i, true); + } else { + red_enable_can_transceiver(i, enabled); + } + } +} + +void red_set_led(uint8_t color, bool enabled) { + switch (color) { + case LED_RED: + set_gpio_output(GPIOE, 4, !enabled); + break; + case LED_GREEN: + set_gpio_output(GPIOE, 3, !enabled); + break; + case LED_BLUE: + set_gpio_output(GPIOE, 2, !enabled); + break; + default: + break; + } +} + +void red_set_usb_load_switch(bool enabled) { + set_gpio_output(GPIOB, 14, !enabled); +} + +void red_set_usb_power_mode(uint8_t mode) { + bool valid = false; + switch (mode) { + case USB_POWER_CLIENT: + red_set_usb_load_switch(false); + valid = true; + break; + case USB_POWER_CDP: + red_set_usb_load_switch(true); + valid = true; + break; + default: + break; + } + if (valid) { + usb_power_mode = mode; + } +} + +void red_set_can_mode(uint8_t mode) { + switch (mode) { + case CAN_MODE_NORMAL: + case CAN_MODE_OBD_CAN2: + if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(car_harness_status == HARNESS_STATUS_FLIPPED)) { + // B12,B13: disable normal mode + set_gpio_pullup(GPIOB, 12, PULL_NONE); + set_gpio_mode(GPIOB, 12, MODE_ANALOG); + + set_gpio_pullup(GPIOB, 13, PULL_NONE); + set_gpio_mode(GPIOB, 13, MODE_ANALOG); + + // B5,B6: FDCAN2 mode + set_gpio_pullup(GPIOB, 5, PULL_NONE); + set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); + + set_gpio_pullup(GPIOB, 6, PULL_NONE); + set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); + } else { + // B5,B6: disable normal mode + set_gpio_pullup(GPIOB, 5, PULL_NONE); + set_gpio_mode(GPIOB, 5, MODE_ANALOG); + + set_gpio_pullup(GPIOB, 6, PULL_NONE); + set_gpio_mode(GPIOB, 6, MODE_ANALOG); + // B12,B13: FDCAN2 mode + set_gpio_pullup(GPIOB, 12, PULL_NONE); + set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2); + + set_gpio_pullup(GPIOB, 13, PULL_NONE); + set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2); + } + break; + default: + break; + } +} + +bool red_check_ignition(void) { + // ignition is checked through harness + return harness_check_ignition(); +} + +void red_init(void) { + common_init_gpio(); + + //C4,A1: OBD_SBU1, OBD_SBU2 + set_gpio_pullup(GPIOC, 4, PULL_NONE); + set_gpio_mode(GPIOC, 4, MODE_ANALOG); + + set_gpio_pullup(GPIOA, 1, PULL_NONE); + set_gpio_mode(GPIOA, 1, MODE_ANALOG); + + //C10,C11 : OBD_SBU1_RELAY, OBD_SBU2_RELAY + set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_pullup(GPIOC, 10, PULL_NONE); + set_gpio_mode(GPIOC, 10, MODE_OUTPUT); + set_gpio_output(GPIOC, 10, 1); + + set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_pullup(GPIOC, 11, PULL_NONE); + set_gpio_mode(GPIOC, 11, MODE_OUTPUT); + set_gpio_output(GPIOC, 11, 1); + + // Turn on USB load switch. + red_set_usb_load_switch(true); + + // Set right power mode + red_set_usb_power_mode(USB_POWER_CDP); + + // Initialize harness + harness_init(); + + // Enable CAN transceivers + red_enable_can_transceivers(true); + + // Disable LEDs + red_set_led(LED_RED, false); + red_set_led(LED_GREEN, false); + red_set_led(LED_BLUE, false); + + // Set normal CAN mode + red_set_can_mode(CAN_MODE_NORMAL); + + // flip CAN0 and CAN2 if we are flipped + if (car_harness_status == HARNESS_STATUS_FLIPPED) { + can_flip_buses(0, 2); + } +} + +const harness_configuration red_harness_config = { + .has_harness = true, + .GPIO_SBU1 = GPIOC, + .GPIO_SBU2 = GPIOA, + .GPIO_relay_SBU1 = GPIOC, + .GPIO_relay_SBU2 = GPIOC, + .pin_SBU1 = 4, + .pin_SBU2 = 1, + .pin_relay_SBU1 = 10, + .pin_relay_SBU2 = 11, + .adc_channel_SBU1 = 4, //ADC12_INP4 + .adc_channel_SBU2 = 17 //ADC1_INP17 +}; + +const board board_red = { + .board_type = "Red", + .harness_config = &red_harness_config, + .has_gps = false, + .has_hw_gmlan = false, + .has_obd = true, + .has_lin = false, + .has_rtc = false, + .init = red_init, + .enable_can_transceiver = red_enable_can_transceiver, + .enable_can_transceivers = red_enable_can_transceivers, + .set_led = red_set_led, + .set_usb_power_mode = red_set_usb_power_mode, + .set_gps_mode = unused_set_gps_mode, + .set_can_mode = red_set_can_mode, + .usb_power_mode_tick = unused_usb_power_mode_tick, + .check_ignition = red_check_ignition, + .read_current = unused_read_current, + .set_fan_power = unused_set_fan_power, + .set_ir_power = unused_set_ir_power, + .set_phone_power = unused_set_phone_power, + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren +}; diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index dc5fbd493..d8f0e0c84 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -173,19 +173,6 @@ void uno_set_fan_power(uint8_t percentage){ fan_set_power(percentage); } -uint32_t uno_read_current(void){ - // No current sense on Uno - return 0U; -} - -void uno_set_clock_source_mode(uint8_t mode){ - UNUSED(mode); -} - -void uno_set_siren(bool enabled){ - UNUSED(enabled); -} - void uno_init(void) { common_init_gpio(); @@ -292,10 +279,10 @@ const board board_uno = { .set_can_mode = uno_set_can_mode, .usb_power_mode_tick = uno_usb_power_mode_tick, .check_ignition = uno_check_ignition, - .read_current = uno_read_current, + .read_current = unused_read_current, .set_fan_power = uno_set_fan_power, .set_ir_power = uno_set_ir_power, .set_phone_power = uno_set_phone_power, - .set_clock_source_mode = uno_set_clock_source_mode, - .set_siren = uno_set_siren + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren }; diff --git a/panda/board/boards/unused_funcs.h b/panda/board/boards/unused_funcs.h new file mode 100644 index 000000000..e9d59c69a --- /dev/null +++ b/panda/board/boards/unused_funcs.h @@ -0,0 +1,31 @@ +void unused_set_gps_mode(uint8_t mode) { + UNUSED(mode); +} + +void unused_usb_power_mode_tick(uint32_t uptime) { + UNUSED(uptime); +} + +void unused_set_ir_power(uint8_t percentage) { + UNUSED(percentage); +} + +void unused_set_fan_power(uint8_t percentage) { + UNUSED(percentage); +} + +void unused_set_phone_power(bool enabled) { + UNUSED(enabled); +} + +void unused_set_clock_source_mode(uint8_t mode) { + UNUSED(mode); +} + +void unused_set_siren(bool enabled) { + UNUSED(enabled); +} + +uint32_t unused_read_current(void) { + return 0U; +} diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 14f026fa8..560a3d4a5 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -151,35 +151,11 @@ uint32_t white_read_current(void){ return adc_get(ADCCHAN_CURRENT); } -void white_usb_power_mode_tick(uint32_t uptime){ - UNUSED(uptime); -} - -void white_set_ir_power(uint8_t percentage){ - UNUSED(percentage); -} - -void white_set_fan_power(uint8_t percentage){ - UNUSED(percentage); -} - bool white_check_ignition(void){ // ignition is on PA1 return !get_gpio_input(GPIOA, 1); } -void white_set_phone_power(bool enabled){ - UNUSED(enabled); -} - -void white_set_clock_source_mode(uint8_t mode){ - UNUSED(mode); -} - -void white_set_siren(bool enabled){ - UNUSED(enabled); -} - void white_grey_common_init(void) { common_init_gpio(); @@ -277,12 +253,12 @@ const board board_white = { .set_usb_power_mode = white_set_usb_power_mode, .set_gps_mode = white_set_gps_mode, .set_can_mode = white_set_can_mode, - .usb_power_mode_tick = white_usb_power_mode_tick, + .usb_power_mode_tick = unused_usb_power_mode_tick, .check_ignition = white_check_ignition, .read_current = white_read_current, - .set_fan_power = white_set_fan_power, - .set_ir_power = white_set_ir_power, - .set_phone_power = white_set_phone_power, - .set_clock_source_mode = white_set_clock_source_mode, - .set_siren = white_set_siren + .set_fan_power = unused_set_fan_power, + .set_ir_power = unused_set_ir_power, + .set_phone_power = unused_set_phone_power, + .set_clock_source_mode = unused_set_clock_source_mode, + .set_siren = unused_set_siren }; diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c index 1541a31d2..a31721232 100644 --- a/panda/board/bootstub.c +++ b/panda/board/bootstub.c @@ -17,7 +17,7 @@ #include "obj/cert.h" #include "obj/gitversion.h" -#include "spi_flasher.h" +#include "flasher.h" void __initialize_hardware_early(void) { early_initialization(); diff --git a/panda/board/build_all.sh b/panda/board/build_all.sh new file mode 100755 index 000000000..b7e681108 --- /dev/null +++ b/panda/board/build_all.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env sh +set -e + +scons -u +PANDA_H7=1 scons -u +PEDAL=1 scons -u +PEDAL=1 PEDAL_USB=1 scons -u diff --git a/panda/board/config.h b/panda/board/config.h index d66c65c52..d62bcb95a 100644 --- a/panda/board/config.h +++ b/panda/board/config.h @@ -34,7 +34,21 @@ #define MAX_RESP_LEN 0x40U +#define GET_BUS(msg) (((msg)->RDTR >> 4) & 0xFF) +#define GET_LEN(msg) ((msg)->RDTR & 0xF) +#define GET_ADDR(msg) ((((msg)->RIR & 4) != 0) ? ((msg)->RIR >> 3) : ((msg)->RIR >> 21)) +#define GET_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) +#define GET_BYTES_04(msg) ((msg)->RDLR) +#define GET_BYTES_48(msg) ((msg)->RDHR) +#define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) + +#define CAN_INIT_TIMEOUT_MS 500U + #include -#include "stm32fx/stm32fx_config.h" +#ifdef STM32H7 + #include "stm32h7/stm32h7_config.h" +#else + #include "stm32fx/stm32fx_config.h" +#endif #endif diff --git a/panda/board/drivers/can.h b/panda/board/drivers/bxcan.h similarity index 54% rename from panda/board/drivers/can.h rename to panda/board/drivers/bxcan.h index 6ec13362a..d631f0c72 100644 --- a/panda/board/drivers/can.h +++ b/panda/board/drivers/bxcan.h @@ -2,163 +2,7 @@ // CAN2_TX, CAN2_RX0, CAN2_SCE // CAN3_TX, CAN3_RX0, CAN3_SCE -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CAN_FIFOMailBox_TypeDef *elems; -} can_ring; - -#define CAN_BUS_RET_FLAG 0x80U -#define CAN_BUS_NUM_MASK 0x7FU - -#define BUS_MAX 4U - -uint32_t can_rx_errs = 0; -uint32_t can_send_errs = 0; -uint32_t can_fwd_errs = 0; -uint32_t gmlan_send_errs = 0; - -extern int can_live; -extern int pending_can_live; - -// must reinit after changing these -extern int can_loopback; -extern int can_silent; -extern uint32_t can_speed[4]; - -void can_set_forwarding(int from, int to); - -bool can_init(uint8_t can_number); -void can_init_all(void); -bool can_tx_check_min_slots_free(uint32_t min); -void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number, bool skip_tx_hook); -bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem); - -// Ignition detected from CAN meessages -bool ignition_can = false; -bool ignition_cadillac = false; -uint32_t ignition_can_cnt = 0U; - -// end API - -#define ALL_CAN_SILENT 0xFF -#define ALL_CAN_LIVE 0 - -int can_live = 0; -int pending_can_live = 0; -int can_loopback = 0; -int can_silent = ALL_CAN_SILENT; - -// ********************* instantiate queues ********************* -#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(rx_q, 0x1000) -can_buffer(tx1_q, 0x100) -can_buffer(tx2_q, 0x100) -can_buffer(tx3_q, 0x100) -can_buffer(txgmlan_q, 0x100) -// FIXME: -// cppcheck-suppress misra-c2012-9.3 -can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; - -// global CAN stats -int can_rx_cnt = 0; -int can_tx_cnt = 0; -int can_txd_cnt = 0; -int can_err_cnt = 0; -int can_overflow_cnt = 0; - -// ********************* interrupt safe queue ********************* -bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = 0; - - ENTER_CRITICAL(); - 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; - } - EXIT_CRITICAL(); - - return ret; -} - -bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = false; - uint32_t next_w_ptr; - - ENTER_CRITICAL(); - 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; - } - EXIT_CRITICAL(); - if (!ret) { - can_overflow_cnt++; - #ifdef DEBUG - puts("can_push failed!\n"); - #endif - } - return ret; -} - -uint32_t can_slots_empty(can_ring *q) { - uint32_t ret = 0; - - ENTER_CRITICAL(); - if (q->w_ptr >= q->r_ptr) { - ret = q->fifo_size - 1U - q->w_ptr + q->r_ptr; - } else { - ret = q->r_ptr - q->w_ptr - 1U; - } - EXIT_CRITICAL(); - - return ret; -} - -void can_clear(can_ring *q) { - ENTER_CRITICAL(); - q->w_ptr = 0; - q->r_ptr = 0; - EXIT_CRITICAL(); -} - -// assign CAN numbering -// bus num: Can bus number on ODB connector. 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'. -// can_forwarding: Given a bus num, lookup bus num to forward to. -1 means no forward. - -// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3}; -uint8_t bus_lookup[] = {0,1,2}; -uint8_t can_num_lookup[] = {0,1,2,-1}; -int8_t can_forwarding[] = {-1,-1,-1,-1}; -uint32_t can_speed[] = {5000, 5000, 5000, 333}; -#define CAN_MAX 3U - -#define CANIF_FROM_CAN_NUM(num) (cans[num]) -#define CAN_NUM_FROM_CANIF(CAN) ((CAN)==CAN1 ? 0 : ((CAN) == CAN2 ? 1 : 2)) -#define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num]) -#define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num]) - -void process_can(uint8_t can_number); bool can_set_speed(uint8_t can_number) { bool ret = true; @@ -169,22 +13,6 @@ bool can_set_speed(uint8_t can_number) { return ret; } -void can_init_all(void) { - bool ret = true; - for (uint8_t i=0U; i < CAN_MAX; i++) { - can_clear(can_queues[i]); - ret &= can_init(i); - } - UNUSED(ret); -} - -void can_flip_buses(uint8_t bus1, uint8_t bus2){ - bus_lookup[bus1] = bus2; - bus_lookup[bus2] = bus1; - can_num_lookup[bus1] = bus2; - can_num_lookup[bus2] = bus1; -} - // TODO: Cleanup with new abstraction void can_set_gmlan(uint8_t bus) { if(current_board->has_hw_gmlan){ @@ -323,34 +151,6 @@ void process_can(uint8_t can_number) { } } -void ignition_can_hook(CAN_FIFOMailBox_TypeDef *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - - ignition_can_cnt = 0U; // reset counter - - if (bus == 0) { - // TODO: verify on all supported GM models that we can reliably detect ignition using only this signal, - // since the 0x1F1 signal can briefly go low immediately after ignition - if ((addr == 0x160) && (len == 5)) { - // this message isn't all zeros when ignition is on - ignition_cadillac = GET_BYTES_04(to_push) != 0; - } - // GM exception - if ((addr == 0x1F1) && (len == 8)) { - // Bit 5 is ignition "on" - bool ignition_gm = ((GET_BYTE(to_push, 0) & 0x20) != 0); - ignition_can = ignition_gm || ignition_cadillac; - } - // Tesla exception - if ((addr == 0x348) && (len == 8)) { - // GTW_status - ignition_can = (GET_BYTE(to_push, 0) & 0x1) != 0; - } - } -} - // CAN receive handlers // blink blue when we are receiving CAN messages void can_rx(uint8_t can_number) { @@ -406,34 +206,6 @@ 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(CAN3); } -bool can_tx_check_min_slots_free(uint32_t min) { - return - (can_slots_empty(&can_tx1_q) >= min) && - (can_slots_empty(&can_tx2_q) >= min) && - (can_slots_empty(&can_tx3_q) >= min) && - (can_slots_empty(&can_txgmlan_q) >= min); -} - -void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number, bool skip_tx_hook) { - if (skip_tx_hook || safety_tx_hook(to_push) != 0) { - if (bus_number < BUS_MAX) { - // add CAN packet to send queue - // bus number isn't passed through - to_push->RDTR &= 0xF; - if ((bus_number == 3U) && (can_num_lookup[3] == 0xFFU)) { - gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; - } else { - can_fwd_errs += can_push(can_queues[bus_number], to_push) ? 0U : 1U; - process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); - } - } - } -} - -void can_set_forwarding(int from, int to) { - can_forwarding[from] = to; -} - bool can_init(uint8_t can_number) { bool ret = false; diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h new file mode 100644 index 000000000..73d37aa84 --- /dev/null +++ b/panda/board/drivers/can_common.h @@ -0,0 +1,222 @@ +typedef struct { + volatile uint32_t w_ptr; + volatile uint32_t r_ptr; + uint32_t fifo_size; + CAN_FIFOMailBox_TypeDef *elems; +} can_ring; + +#define CAN_BUS_RET_FLAG 0x80U +#define CAN_BUS_NUM_MASK 0x7FU + +#define BUS_MAX 4U + +uint32_t can_rx_errs = 0; +uint32_t can_send_errs = 0; +uint32_t can_fwd_errs = 0; +uint32_t gmlan_send_errs = 0; + +extern int can_live; +extern int pending_can_live; + +// must reinit after changing these +extern int can_loopback; +extern int can_silent; +extern uint32_t can_speed[4]; +extern uint32_t can_data_speed[3]; + +// Ignition detected from CAN meessages +bool ignition_can = false; +bool ignition_cadillac = 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_loopback = 0; +int can_silent = ALL_CAN_SILENT; + +// ******************* functions prototypes ********************* +bool can_init(uint8_t can_number); +void process_can(uint8_t can_number); + +// ********************* instantiate queues ********************* +#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(rx_q, 0x1000) +can_buffer(tx1_q, 0x100) +can_buffer(tx2_q, 0x100) +can_buffer(tx3_q, 0x100) +can_buffer(txgmlan_q, 0x100) +// FIXME: +// cppcheck-suppress misra-c2012-9.3 +can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; + +// global CAN stats +int can_rx_cnt = 0; +int can_tx_cnt = 0; +int can_txd_cnt = 0; +int can_err_cnt = 0; +int can_overflow_cnt = 0; + +// ********************* interrupt safe queue ********************* +bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + bool ret = 0; + + ENTER_CRITICAL(); + 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; + } + EXIT_CRITICAL(); + + return ret; +} + +bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + bool ret = false; + uint32_t next_w_ptr; + + ENTER_CRITICAL(); + 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; + } + EXIT_CRITICAL(); + if (!ret) { + can_overflow_cnt++; + #ifdef DEBUG + puts("can_push failed!\n"); + #endif + } + return ret; +} + +uint32_t can_slots_empty(can_ring *q) { + uint32_t ret = 0; + + ENTER_CRITICAL(); + if (q->w_ptr >= q->r_ptr) { + ret = q->fifo_size - 1U - q->w_ptr + q->r_ptr; + } else { + ret = q->r_ptr - q->w_ptr - 1U; + } + EXIT_CRITICAL(); + + return ret; +} + +void can_clear(can_ring *q) { + ENTER_CRITICAL(); + q->w_ptr = 0; + q->r_ptr = 0; + EXIT_CRITICAL(); +} + +// assign CAN numbering +// bus num: Can bus number on ODB connector. 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'. +// can_forwarding: Given a bus num, lookup bus num to forward to. -1 means no forward. + +// Helpers +// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 +uint8_t bus_lookup[] = {0,1,2}; +uint8_t can_num_lookup[] = {0,1,2,-1}; +int8_t can_forwarding[] = {-1,-1,-1,-1}; +uint32_t can_speed[] = {5000, 5000, 5000, 333}; +uint32_t can_data_speed[] = {5000, 5000, 5000}; //For CAN FD with BRS only +#define CAN_MAX 3U + +#define CANIF_FROM_CAN_NUM(num) (cans[num]) +#define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num]) +#define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num]) + +void can_init_all(void) { + bool ret = true; + for (uint8_t i=0U; i < CAN_MAX; i++) { + can_clear(can_queues[i]); + ret &= can_init(i); + } + UNUSED(ret); +} + +void can_flip_buses(uint8_t bus1, uint8_t bus2){ + bus_lookup[bus1] = bus2; + bus_lookup[bus2] = bus1; + can_num_lookup[bus1] = bus2; + can_num_lookup[bus2] = bus1; +} + +void ignition_can_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus = GET_BUS(to_push); + int addr = GET_ADDR(to_push); + int len = GET_LEN(to_push); + + ignition_can_cnt = 0U; // reset counter + + if (bus == 0) { + // TODO: verify on all supported GM models that we can reliably detect ignition using only this signal, + // since the 0x1F1 signal can briefly go low immediately after ignition + if ((addr == 0x160) && (len == 5)) { + // this message isn't all zeros when ignition is on + ignition_cadillac = GET_BYTES_04(to_push) != 0; + } + // GM exception + if ((addr == 0x1F1) && (len == 8)) { + // Bit 5 is ignition "on" + bool ignition_gm = ((GET_BYTE(to_push, 0) & 0x20) != 0); + ignition_can = ignition_gm || ignition_cadillac; + } + // Tesla exception + if ((addr == 0x348) && (len == 8)) { + // GTW_status + ignition_can = (GET_BYTE(to_push, 0) & 0x1) != 0; + } + } +} + +bool can_tx_check_min_slots_free(uint32_t min) { + return + (can_slots_empty(&can_tx1_q) >= min) && + (can_slots_empty(&can_tx2_q) >= min) && + (can_slots_empty(&can_tx3_q) >= min) && + (can_slots_empty(&can_txgmlan_q) >= min); +} + +void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number, bool skip_tx_hook) { + if (skip_tx_hook || safety_tx_hook(to_push) != 0) { + if (bus_number < BUS_MAX) { + // add CAN packet to send queue + // bus number isn't passed through + to_push->RDTR &= 0xF; + if ((bus_number == 3U) && (can_num_lookup[3] == 0xFFU)) { + gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; + } else { + can_fwd_errs += can_push(can_queues[bus_number], to_push) ? 0U : 1U; + process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); + } + } + } +} + +void can_set_forwarding(int from, int to) { + can_forwarding[from] = to; +} diff --git a/panda/board/drivers/fdcan.h b/panda/board/drivers/fdcan.h new file mode 100644 index 000000000..d9eed3efc --- /dev/null +++ b/panda/board/drivers/fdcan.h @@ -0,0 +1,203 @@ +// IRQs: FDCAN1_IT0, FDCAN1_IT1 +// FDCAN2_IT0, FDCAN2_IT1 +// FDCAN3_IT0, FDCAN3_IT1 + +#define BUS_OFF_FAIL_LIMIT 2U +uint8_t bus_off_err[] = {0U, 0U, 0U}; + +FDCAN_GlobalTypeDef *cans[] = {FDCAN1, FDCAN2, FDCAN3}; + +bool can_set_speed(uint8_t can_number) { + bool ret = true; + FDCAN_GlobalTypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + + ret &= llcan_set_speed(CANx, can_speed[bus_number], can_data_speed[bus_number], can_loopback, (unsigned int)(can_silent) & (1U << can_number)); + return ret; +} + +void can_set_gmlan(uint8_t bus) { + UNUSED(bus); + puts("GMLAN not available on red panda\n"); +} + +void cycle_transceiver(uint8_t can_number) { + // FDCAN1 = trans 1, FDCAN3 = trans 3, FDCAN2 = trans 2 normal or 4 flipped harness + uint8_t transceiver_number = can_number; + if (can_number == 2U) { + uint8_t flip = (car_harness_status == HARNESS_STATUS_FLIPPED) ? 2U : 0U; + transceiver_number += flip; + } + current_board->enable_can_transceiver(transceiver_number, false); + delay(20000); + current_board->enable_can_transceiver(transceiver_number, true); + bus_off_err[can_number] = 0U; + puts("Cycled transceiver number: "); puth(transceiver_number); puts("\n"); +} + +// ***************************** CAN ***************************** +void process_can(uint8_t can_number) { + if (can_number != 0xffU) { + ENTER_CRITICAL(); + + FDCAN_GlobalTypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + + CANx->IR |= FDCAN_IR_TFE; // Clear Tx FIFO Empty flag + + if ((CANx->TXFQS & FDCAN_TXFQS_TFQF) == 0) { + CAN_FIFOMailBox_TypeDef to_send; + if (can_pop(can_queues[bus_number], &to_send)) { + can_tx_cnt += 1; + uint32_t TxFIFOSA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET) + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); + uint8_t tx_index = (CANx->TXFQS >> FDCAN_TXFQS_TFQPI_Pos) & 0x1F; + // only send if we have received a packet + CAN_FIFOMailBox_TypeDef *fifo; + fifo = (CAN_FIFOMailBox_TypeDef *)(TxFIFOSA + (tx_index * FDCAN_TX_FIFO_EL_SIZE)); + + // Convert from "mailbox type" + fifo->RIR = ((to_send.RIR & 0x6) << 28) | (to_send.RIR >> 3); // identifier format and frame type | identifier + //REDEBUG: enable CAN FD and BRS for test purposes + //fifo->RDTR = ((to_send.RDTR & 0xF) << 16) | ((to_send.RDTR) >> 16) | (1U << 21) | (1U << 20); // DLC (length) | timestamp | enable CAN FD | enable BRS + fifo->RDTR = ((to_send.RDTR & 0xF) << 16) | ((to_send.RDTR) >> 16); // DLC (length) | timestamp + fifo->RDLR = to_send.RDLR; + fifo->RDHR = to_send.RDHR; + + CANx->TXBAR = (1UL << tx_index); + + // Send back to USB + can_txd_cnt += 1; + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = to_send.RIR; + to_push.RDTR = (to_send.RDTR & 0xFFFF000FU) | ((CAN_BUS_RET_FLAG | bus_number) << 4); + to_push.RDLR = to_send.RDLR; + to_push.RDHR = to_send.RDHR; + can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; + + if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_BULK_TRANSFER)) { + usb_outep3_resume_if_paused(); + } + } + } + + // Recover after Bus-off state + if (((CANx->PSR & FDCAN_PSR_BO) != 0) && ((CANx->CCCR & FDCAN_CCCR_INIT) != 0)) { + bus_off_err[can_number] += 1U; + puts("CAN is in Bus_Off state! Resetting... CAN number: "); puth(can_number); puts("\n"); + if (bus_off_err[can_number] > BUS_OFF_FAIL_LIMIT) { + cycle_transceiver(can_number); + } + CANx->IR = 0xFFC60000U; // Reset all flags(Only errors!) + CANx->CCCR &= ~(FDCAN_CCCR_INIT); + uint32_t timeout_counter = 0U; + while((CANx->CCCR & FDCAN_CCCR_INIT) != 0) { + // Delay for about 1ms + delay(10000); + timeout_counter++; + + if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ + puts(CAN_NAME_FROM_CANIF(CANx)); puts(" Bus_Off reset timed out!\n"); + break; + } + } + } + EXIT_CRITICAL(); + } +} + +// CAN receive handlers +// blink blue when we are receiving CAN messages +void can_rx(uint8_t can_number) { + FDCAN_GlobalTypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + uint8_t rx_fifo_idx; + + // Rx FIFO 0 new message + if((CANx->IR & FDCAN_IR_RF0N) != 0) { + CANx->IR |= FDCAN_IR_RF0N; + while((CANx->RXF0S & FDCAN_RXF0S_F0FL) != 0) { + can_rx_cnt += 1; + + // can is live + pending_can_live = 1; + + // getting new message index (0 to 63) + rx_fifo_idx = (uint8_t)((CANx->RXF0S >> FDCAN_RXF0S_F0GI_Pos) & 0x3F); + + uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET); + CAN_FIFOMailBox_TypeDef to_push; + CAN_FIFOMailBox_TypeDef *fifo; + + // getting address + fifo = (CAN_FIFOMailBox_TypeDef *)(RxFIFO0SA + (rx_fifo_idx * FDCAN_RX_FIFO_0_EL_SIZE)); + + // Need to convert real CAN frame format to mailbox "type" + to_push.RIR = ((fifo->RIR >> 28) & 0x6) | (fifo->RIR << 3); // identifier format and frame type | identifier + to_push.RDTR = ((fifo->RDTR >> 16) & 0xF) | (fifo->RDTR << 16); // DLC (length) | timestamp + to_push.RDLR = fifo->RDLR; + to_push.RDHR = fifo->RDHR; + + // modify RDTR for our API + to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4); + + // forwarding (panda only) + int bus_fwd_num = (can_forwarding[bus_number] != -1) ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push); + if (bus_fwd_num != -1) { + CAN_FIFOMailBox_TypeDef to_send; + to_send.RIR = to_push.RIR; + to_send.RDTR = to_push.RDTR; + to_send.RDLR = to_push.RDLR; + to_send.RDHR = to_push.RDHR; + can_send(&to_send, bus_fwd_num, true); + } + + can_rx_errs += safety_rx_hook(&to_push) ? 0U : 1U; + ignition_can_hook(&to_push); + + current_board->set_led(LED_BLUE, true); + can_send_errs += can_push(&can_rx_q, &to_push) ? 0U : 1U; + + // update read index + CANx->RXF0A = rx_fifo_idx; + } + + } else if((CANx->IR & (FDCAN_IR_PEA | FDCAN_IR_PED | FDCAN_IR_RF0L | FDCAN_IR_RF0F | FDCAN_IR_EW | FDCAN_IR_MRAF | FDCAN_IR_TOO)) != 0) { + #ifdef DEBUG + puts("FDCAN error, FDCAN_IR: ");puth(CANx->IR);puts("\n"); + #endif + CANx->IR |= (FDCAN_IR_PEA | FDCAN_IR_PED | FDCAN_IR_RF0L | FDCAN_IR_RF0F | FDCAN_IR_EW | FDCAN_IR_MRAF | FDCAN_IR_TOO); // Clean all error flags + can_err_cnt += 1; + } else { + + } + +} + +void FDCAN1_IT0_IRQ_Handler(void) { can_rx(0); } +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); } + +void FDCAN3_IT0_IRQ_Handler(void) { can_rx(2); } +void FDCAN3_IT1_IRQ_Handler(void) { process_can(2); } + +bool can_init(uint8_t can_number) { + bool ret = false; + + REGISTER_INTERRUPT(FDCAN1_IT0_IRQn, FDCAN1_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) + REGISTER_INTERRUPT(FDCAN1_IT1_IRQn, FDCAN1_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) + REGISTER_INTERRUPT(FDCAN2_IT0_IRQn, FDCAN2_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) + REGISTER_INTERRUPT(FDCAN2_IT1_IRQn, FDCAN2_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) + REGISTER_INTERRUPT(FDCAN3_IT0_IRQn, FDCAN3_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) + REGISTER_INTERRUPT(FDCAN3_IT1_IRQn, FDCAN3_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) + + if (can_number != 0xffU) { + FDCAN_GlobalTypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); + ret &= can_set_speed(can_number); + ret &= llcan_init(CANx); + // in case there are queued up messages + process_can(can_number); + } + return ret; +} diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index af7f99954..ecb3241a7 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -38,6 +38,7 @@ typedef struct uart_ring { // ***************************** 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 ******************************** @@ -138,11 +139,6 @@ void uart_flush_sync(uart_ring *q) { } } -void uart_send_break(uart_ring *u) { - while ((u->uart->CR1 & USART_CR1_SBK) != 0); - u->uart->CR1 |= USART_CR1_SBK; -} - void clear_uart_buff(uart_ring *q) { ENTER_CRITICAL(); q->w_ptr_tx = 0; diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index d08eed2d6..abe88c7e1 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -123,7 +123,7 @@ uint8_t device_desc[] = { 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size TOUSBORDER(USB_VID), // idVendor TOUSBORDER(USB_PID), // idProduct - 0x00, 0x23, // bcdDevice + 0x00, 0x00, // bcdDevice 0x01, 0x02, // Manufacturer, Product 0x03, 0x01 // Serial Number, Num Configurations }; @@ -526,6 +526,8 @@ void usb_setup(void) { case USB_DESC_TYPE_DEVICE: //puts(" writing device descriptor\n"); + // set bcdDevice to hardware type + device_desc[13] = hw_type; // setup transfer USB_WritePacket(device_desc, MIN(sizeof(device_desc), setup.b.wLength.w), 0); USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; diff --git a/panda/board/flash_h7.sh b/panda/board/flash_h7.sh new file mode 100755 index 000000000..9b7566189 --- /dev/null +++ b/panda/board/flash_h7.sh @@ -0,0 +1,5 @@ +#!/usr/bin/env sh +set -e + +PANDA_GEN3=1 scons -u +PYTHONPATH=.. python3 -c "from python import Panda; Panda().flash('obj/panda_h7.bin.signed')" diff --git a/panda/board/spi_flasher.h b/panda/board/flasher.h similarity index 85% rename from panda/board/spi_flasher.h rename to panda/board/flasher.h index cbc1c428c..764eddb93 100644 --- a/panda/board/spi_flasher.h +++ b/panda/board/flasher.h @@ -1,6 +1,6 @@ // flasher state variables uint32_t *prog_ptr = NULL; -int unlocked = 0; +bool unlocked = false; #ifdef uart_ring void debug_ring_callback(uart_ring *ring) {} @@ -26,32 +26,27 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xb1: unlock flash case 0xb1: - if (FLASH->CR & FLASH_CR_LOCK) { - FLASH->KEYR = 0x45670123; - FLASH->KEYR = 0xCDEF89AB; + if (flash_is_locked()) { + flash_unlock(); resp[1] = 0xff; } current_board->set_led(LED_GREEN, 1); - unlocked = 1; - prog_ptr = (uint32_t *)0x8004000; + unlocked = true; + prog_ptr = (uint32_t *)APP_START_ADDRESS; break; // **** 0xb2: erase sector case 0xb2: sec = setup->b.wValue.w; - // don't erase the bootloader - if (sec != 0 && sec < 12 && unlocked) { - FLASH->CR = (sec << 3) | FLASH_CR_SER; - FLASH->CR |= FLASH_CR_STRT; - while (FLASH->SR & FLASH_SR_BSY); + if (flash_erase_sector(sec, unlocked)) { resp[1] = 0xff; } break; // **** 0xd0: fetch serial number case 0xd0: - #ifdef STM32F4 + #ifndef STM32F2 // addresses are OTP if (setup->b.wValue.w == 1) { - memcpy(resp, (void *)0x1fff79c0, 0x10); + memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); resp_len = 0x10; } else { get_provision_chunk(resp); @@ -93,6 +88,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xd8: reset ST case 0xd8: + flush_write_buffer(); NVIC_SystemReset(); break; } @@ -122,11 +118,7 @@ void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { UNUSED(hardwired); current_board->set_led(LED_RED, 0); for (int i = 0; i < len/4; i++) { - // program byte 1 - FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; - - *prog_ptr = *(uint32_t*)(usbdata+(i*4)); - while (FLASH->SR & FLASH_SR_BSY); + flash_write_word(prog_ptr, *(uint32_t*)(usbdata+(i*4))); //*(uint64_t*)(&spi_tx_buf[0x30+(i*4)]) = *prog_ptr; prog_ptr++; @@ -153,7 +145,7 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { #ifdef PEDAL -#include "stm32fx/llcan.h" +#include "stm32fx/llbxcan.h" #define CAN CAN1 #define CAN_BL_INPUT 0x1 @@ -278,10 +270,7 @@ void soft_flasher_start(void) { enter_bootloader_mode = 0; - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + flasher_peripherals_init(); // pedal has the canloader #ifdef PEDAL @@ -297,23 +286,8 @@ void soft_flasher_start(void) { llcan_init(CAN1); #endif - // A4,A5,A6,A7: setup SPI - set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); - - // A2,A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); - - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; - - // flasher - //spi_init(); + gpio_usart2_init(); + gpio_usb_init(); // enable USB usb_init(); diff --git a/panda/board/main.c b/panda/board/main.c index d9012d80b..651d25747 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -12,7 +12,13 @@ #include "power_saving.h" #include "safety.h" -#include "drivers/can.h" +#include "drivers/can_common.h" + +#ifdef STM32H7 + #include "drivers/fdcan.h" +#else + #include "drivers/bxcan.h" +#endif #include "obj/gitversion.h" @@ -464,6 +470,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) // **** 0xde: set can bitrate case 0xde: if (setup->b.wValue.w < BUS_MAX) { + // TODO: add sanity check, ideally check if value is correct(from array of correct values) can_speed[setup->b.wValue.w] = setup->b.wIndex.w; bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); UNUSED(ret); @@ -617,6 +624,15 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) heartbeat_disabled = true; break; #endif + // **** 0xde: set CAN FD data bitrate + case 0xf9: + if (setup->b.wValue.w < CAN_MAX) { + // TODO: add sanity check, ideally check if value is correct(from array of correct values) + can_data_speed[setup->b.wValue.w] = setup->b.wIndex.w; + bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); + UNUSED(ret); + } + break; default: puts("NO HANDLER "); puth(setup->b.bRequest); diff --git a/panda/board/recover_h7.sh b/panda/board/recover_h7.sh new file mode 100755 index 000000000..737f954a9 --- /dev/null +++ b/panda/board/recover_h7.sh @@ -0,0 +1,11 @@ +#!/usr/bin/env sh +set -e + +DFU_UTIL="dfu-util" + +PANDA_H7=1 scons -u + +PYTHONPATH=.. python3 -c "from python import Panda; Panda().reset(enter_bootstub=True); Panda().reset(enter_bootloader=True)" || true +sleep 1 +$DFU_UTIL -d 0483:df11 -a 0 -s 0x08020000 -D obj/panda_h7.bin.signed +$DFU_UTIL -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.panda_h7.bin diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 0e2acdb46..8566f06a8 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -7,8 +7,8 @@ // brake rising edge // brake > 0mph const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x200, 0, 6}, {0x30C, 0, 8}, {0x33D, 0, 5}}; -const CanMsg HONDA_BG_TX_MSGS[] = {{0xE4, 2, 5}, {0xE5, 2, 8}, {0x296, 0, 4}, {0x33D, 2, 5}}; // Bosch Giraffe -const CanMsg HONDA_BH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}}; // Bosch Harness +const CanMsg HONDA_BG_TX_MSGS[] = {{0xE4, 2, 5}, {0xE5, 2, 8}, {0x296, 0, 4}, {0x33D, 2, 5}, {0x33DA, 2, 5}, {0x33DB, 2, 8}}; // Bosch Giraffe +const CanMsg HONDA_BH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}, {0x33DA, 0, 5}, {0x33DB, 0, 8}}; // Bosch Harness const CanMsg HONDA_BG_LONG_TX_MSGS[] = {{0xE4, 0, 5}, {0x1DF, 0, 8}, {0x1EF, 0, 8}, {0x1FA, 0, 8}, {0x30C, 0, 8}, {0x33D, 0, 5}, {0x39F, 0, 8}, {0x18DAB0F1, 0, 8}}; // Bosch Giraffe w/ gas and brakes const CanMsg HONDA_BH_LONG_TX_MSGS[] = {{0xE4, 1, 5}, {0x1DF, 1, 8}, {0x1EF, 1, 8}, {0x1FA, 1, 8}, {0x30C, 1, 8}, {0x33D, 1, 5}, {0x39F, 1, 8}, {0x18DAB0F1, 1, 8}}; // Bosch Harness w/ gas and brakes @@ -274,7 +274,7 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { } } - // Bosch supplemental control check + // Bosch supplemental control check if (addr == 0xE5) { if ((GET_BYTES_04(to_send) != 0x10800004) || ((GET_BYTES_48(to_send) & 0x00FFFFFF) != 0x0)) { tx = 0; @@ -376,7 +376,7 @@ static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { } if (bus_num == bus_rdr_cam) { int addr = GET_ADDR(to_fwd); - int is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D); + int is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D) || (addr == 0x33DA) || (addr == 0x33DB); if (!is_lkas_msg) { bus_fwd = bus_rdr_car; } diff --git a/panda/board/stm32fx/board.h b/panda/board/stm32fx/board.h index 4cf350536..90aa739fd 100644 --- a/panda/board/stm32fx/board.h +++ b/panda/board/stm32fx/board.h @@ -2,6 +2,7 @@ // Hardware abstraction layer for all different supported boards // // ///////////////////////////////////////////////////////////// // #include "boards/board_declarations.h" +#include "boards/unused_funcs.h" // ///// Board definition and detection ///// // #include "drivers/harness.h" diff --git a/panda/board/stm32fx/inc/stm32f2xx.h b/panda/board/stm32fx/inc/stm32f2xx.h index 19981d493..39346c64c 100644 --- a/panda/board/stm32fx/inc/stm32f2xx.h +++ b/panda/board/stm32fx/inc/stm32f2xx.h @@ -10,8 +10,8 @@ * is using in the C source code, usually in main.c. This file contains: * - Configuration section that allows to select: * - The STM32F2xx device used in the target application - * - To use or not the peripherals drivers in application code(i.e. - * code will be based on direct access to peripherals registers + * - To use or not the peripheral’s drivers in application code(i.e. + * code will be based on direct access to peripheral’s registers * rather than drivers API), this option is controlled by * "#define USE_HAL_DRIVER" * @@ -74,7 +74,7 @@ /* Uncomment the line below according to the target STM32 device used in your application */ -#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) +/* #if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) */ /* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF, STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC, @@ -84,7 +84,7 @@ STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */ /* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE Devices */ -#endif +//#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. @@ -118,14 +118,14 @@ * @{ */ -#if defined(STM32F205xx) - #include "stm32f205xx.h" -#elif defined(STM32F215xx) +#if defined(STM32F215xx) #include "stm32f215xx.h" -#elif defined(STM32F207xx) - #include "stm32f207xx.h" -#elif defined(STM32F217xx) - #include "stm32f217xx.h" +#elif defined(STM32F205xx) + #include "stm32f205xx.h" +// #elif defined(STM32F207xx) +// #include "stm32f207xx.h" +// #elif defined(STM32F217xx) +// #include "stm32f217xx.h" #else #error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)" #endif diff --git a/panda/board/stm32fx/inc/stm32f4xx.h b/panda/board/stm32fx/inc/stm32f4xx.h index 092d8acec..ae7b366af 100644 --- a/panda/board/stm32fx/inc/stm32f4xx.h +++ b/panda/board/stm32fx/inc/stm32f4xx.h @@ -10,8 +10,8 @@ * is using in the C source code, usually in main.c. This file contains: * - Configuration section that allows to select: * - The STM32F4xx device used in the target application - * - To use or not the peripherals drivers in application code(i.e. - * code will be based on direct access to peripherals registers + * - To use or not the peripheral’s drivers in application code(i.e. + * code will be based on direct access to peripheral’s registers * rather than drivers API), this option is controlled by * "#define USE_HAL_DRIVER" * @@ -74,12 +74,12 @@ /* Uncomment the line below according to the target STM32 device used in your application */ -#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \ +/* #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) + !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 */ @@ -109,7 +109,7 @@ /* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG, STM32F413RG, STM32F413VG and STM32F413ZG Devices */ /* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH Devices */ -#endif +//#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. @@ -143,51 +143,51 @@ * @{ */ -#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) +// #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" +#if defined(STM32F413xx) #include "stm32f413xx.h" -#elif defined(STM32F423xx) + #elif defined(STM32F423xx) #include "stm32f423xx.h" #else #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" diff --git a/panda/board/stm32fx/llcan.h b/panda/board/stm32fx/llbxcan.h similarity index 87% rename from panda/board/stm32fx/llcan.h rename to panda/board/stm32fx/llbxcan.h index 78c4c52ca..f1d5187cb 100644 --- a/panda/board/stm32fx/llcan.h +++ b/panda/board/stm32fx/llbxcan.h @@ -8,15 +8,6 @@ // 5000 = 500 kbps #define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) -#define GET_BUS(msg) (((msg)->RDTR >> 4) & 0xFF) -#define GET_LEN(msg) ((msg)->RDTR & 0xF) -#define GET_ADDR(msg) ((((msg)->RIR & 4) != 0) ? ((msg)->RIR >> 3) : ((msg)->RIR >> 21)) -#define GET_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_BYTES_04(msg) ((msg)->RDLR) -#define GET_BYTES_48(msg) ((msg)->RDHR) -#define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) - -#define CAN_INIT_TIMEOUT_MS 500U #define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) void puts(const char *a); diff --git a/panda/board/stm32fx/llflash.h b/panda/board/stm32fx/llflash.h new file mode 100644 index 000000000..61adcd458 --- /dev/null +++ b/panda/board/stm32fx/llflash.h @@ -0,0 +1,28 @@ +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); +} + +void flush_write_buffer(void) { } diff --git a/panda/board/stm32fx/lluart.h b/panda/board/stm32fx/lluart.h index 0fe4ac2d6..69959a76f 100644 --- a/panda/board/stm32fx/lluart.h +++ b/panda/board/stm32fx/lluart.h @@ -42,6 +42,11 @@ void uart_rx_ring(uart_ring *q){ } } +void uart_send_break(uart_ring *u) { + while ((u->uart->CR1 & USART_CR1_SBK) != 0); + u->uart->CR1 |= USART_CR1_SBK; +} + // This function should be called on: // * Half-transfer DMA interrupt // * Full-transfer DMA interrupt diff --git a/panda/board/stm32fx/peripherals.h b/panda/board/stm32fx/peripherals.h index 9522ad3d7..40ef6cb57 100644 --- a/panda/board/stm32fx/peripherals.h +++ b/panda/board/stm32fx/peripherals.h @@ -1,5 +1,18 @@ +void gpio_usb_init(void) { + // A11,A12: USB + set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); + set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); + GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; +} + +void gpio_usart2_init(void) { + // A2,A3: USART 2 for debugging + set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); + set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); +} + // Common GPIO initialization -void common_init_gpio(void){ +void common_init_gpio(void) { // TODO: Is this block actually doing something??? // pull low to hold ESP in reset?? // enable OTG out tied to ground @@ -12,10 +25,7 @@ void common_init_gpio(void){ // C2: Voltage sense line set_gpio_mode(GPIOC, 2, MODE_ANALOG); - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; + gpio_usb_init(); // A9,A10: USART 1 for talking to the GPS set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1); @@ -31,8 +41,15 @@ void common_init_gpio(void){ #endif } +void flasher_peripherals_init(void) { + RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; +} + // Peripheral initialization -void peripherals_init(void){ +void peripherals_init(void) { // enable GPIOB, UART2, CAN, USB clock RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h index 8bcbfa320..0777d2eb2 100644 --- a/panda/board/stm32fx/stm32fx_config.h +++ b/panda/board/stm32fx/stm32fx_config.h @@ -67,8 +67,10 @@ #include "stm32fx/lluart.h" #endif -#ifndef BOOTSTUB - #include "stm32fx/llcan.h" +#ifdef BOOTSTUB + #include "stm32fx/llflash.h" +#else + #include "stm32fx/llbxcan.h" #endif #if defined(PANDA) || defined(BOOTSTUB) || defined(PEDAL_USB) diff --git a/panda/board/stm32fx/stm32fx_flash.ld b/panda/board/stm32fx/stm32fx_flash.ld index e6b2ef09d..bdc23bc8c 100644 --- a/panda/board/stm32fx/stm32fx_flash.ld +++ b/panda/board/stm32fx/stm32fx_flash.ld @@ -35,7 +35,7 @@ ENTRY(Reset_Handler) /* Highest address of the user mode stack */ enter_bootloader_mode = 0x2001FFFC; _estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ -_app_start = 0x08004000; /* Reserve 16K for bootloader */ +_app_start = 0x08004000; /* Reserve Sector 0(16K) for bootloader */ /* Generate a link error if heap and stack don't fit into RAM */ _Min_Heap_Size = 0; /* required amount of heap */ diff --git a/panda/board/stm32h7/board.h b/panda/board/stm32h7/board.h new file mode 100644 index 000000000..769e9789e --- /dev/null +++ b/panda/board/stm32h7/board.h @@ -0,0 +1,36 @@ +// ///////////////////////////////////////////////////////////// // +// Hardware abstraction layer for all different supported boards // +// ///////////////////////////////////////////////////////////// // +#include "boards/board_declarations.h" +#include "boards/unused_funcs.h" + +// ///// Board definition and detection ///// // +#include "drivers/harness.h" +#include "drivers/fan.h" +#include "stm32h7/llfan.h" +#include "stm32h7/llrtc.h" +#include "drivers/rtc.h" +#include "boards/red.h" + +uint8_t 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) { + if(board_id() == 0U){ + hw_type = HW_TYPE_RED_PANDA; + current_board = &board_red; + } else { + hw_type = HW_TYPE_UNKNOWN; + puts("Hardware type is UNKNOWN!\n"); + } +} + +bool has_external_debug_serial = 0; +void detect_external_debug_serial(void) { + // detect if external serial debugging is present + has_external_debug_serial = detect_with_pull(GPIOA, 3, PULL_DOWN); +} diff --git a/panda/board/stm32h7/clock.h b/panda/board/stm32h7/clock.h new file mode 100644 index 000000000..ce692b408 --- /dev/null +++ b/panda/board/stm32h7/clock.h @@ -0,0 +1,54 @@ +void clock_init(void) { + //Set power mode to direct SMPS power supply(depends on the board layout) + register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS + //Set VOS level to VOS0. (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) + register_set(&(PWR->D3CR), PWR_D3CR_VOS_1, 0xC000U); //VOS2 + while ((PWR->CSR1 & PWR_CSR1_ACTVOSRDY) == 0); + while ((PWR->CSR1 & PWR_CSR1_ACTVOS) != (PWR->D3CR & PWR_D3CR_VOS)); // check that VOS level was actually set + // Configure Flash ACR register LATENCY and WRHIGHFREQ (VOS0 range!) + register_set(&(FLASH->ACR), FLASH_ACR_LATENCY_2WS | 0x20U, 0x3FU); // VOS2, AXI 100MHz-150MHz + // enable external oscillator HSE + register_set_bits(&(RCC->CR), RCC_CR_HSEON); + while ((RCC->CR & RCC_CR_HSERDY) == 0); + // Specify the frequency source for PLL1, divider for DIVM1, divider for DIVM2 : HSE, 5, 5 + register_set(&(RCC->PLLCKSELR), RCC_PLLCKSELR_PLLSRC_HSE | RCC_PLLCKSELR_DIVM1_0 | RCC_PLLCKSELR_DIVM1_2 | RCC_PLLCKSELR_DIVM2_0 | RCC_PLLCKSELR_DIVM2_2, 0x3F3F3U); + + // *** PLL1 start *** + // Specify multiplier N and dividers P, Q, R for PLL1 : 48, 1, 5, 2 + register_set(&(RCC->PLL1DIVR), 0x104002FU, 0x7F7FFFFFU); + // Specify the input and output frequency ranges, enable dividers for PLL1 + register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLL1RGE_2 | RCC_PLLCFGR_DIVP1EN | RCC_PLLCFGR_DIVQ1EN | RCC_PLLCFGR_DIVR1EN, 0x7000CU); + // Enable PLL1 + register_set_bits(&(RCC->CR), RCC_CR_PLL1ON); + while((RCC->CR & RCC_CR_PLL1RDY) == 0); + // *** PLL1 end *** + + //////////////OTHER CLOCKS//////////////////// + // RCC HCLK Clock Source / RCC APB3 Clock Source / RCC SYS Clock Source + register_set(&(RCC->D1CFGR), RCC_D1CFGR_HPRE_DIV2 | RCC_D1CFGR_D1PPRE_DIV2 | RCC_D1CFGR_D1CPRE_DIV1, 0xF7FU); + // RCC APB1 Clock Source / RCC APB2 Clock Source + register_set(&(RCC->D2CFGR), RCC_D2CFGR_D2PPRE1_DIV2 | RCC_D2CFGR_D2PPRE2_DIV2, 0x770U); + // RCC APB4 Clock Source + register_set(&(RCC->D3CFGR), RCC_D3CFGR_D3PPRE_DIV2, 0x70U); + // PLL2P for ADC + register_clear_bits(&(RCC->D3CFGR), RCC_D3CCIPR_ADCSEL); + + // Set SysClock source to PLL + register_set(&(RCC->CFGR), RCC_CFGR_SW_PLL1, 0x7U); + while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL1); + + // SYSCFG peripheral clock enable + register_set_bits(&(RCC->AHB4ENR), RCC_APB4ENR_SYSCFGEN); + //////////////END OTHER CLOCKS//////////////////// + + // Configure clock source for USB + register_set(&(RCC->D2CCIP2R), RCC_D2CCIP2R_USBSEL_0, RCC_D2CCIP2R_USBSEL); //PLL1Q + // Configure clock source for FDCAN + register_set(&(RCC->D2CCIP1R), RCC_D2CCIP1R_FDCANSEL_0, RCC_D2CCIP1R_FDCANSEL); //PLL1Q + // Configure clock source for ADC1,2,3 + register_set(&(RCC->D3CCIPR), RCC_D3CCIPR_ADCSEL_1, RCC_D3CCIPR_ADCSEL); //per_ck(currently HSE) + //Enable the Clock Security System + register_set_bits(&(RCC->CR), RCC_CR_CSSHSEON); + //Enable Vdd33usb supply level detector + register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); +} diff --git a/panda/board/stm32h7/inc/cmsis_compiler.h b/panda/board/stm32h7/inc/cmsis_compiler.h new file mode 100644 index 000000000..d0f39eef6 --- /dev/null +++ b/panda/board/stm32h7/inc/cmsis_compiler.h @@ -0,0 +1,284 @@ +/**************************************************************************//** + * @file cmsis_compiler.h + * @brief CMSIS compiler generic header file + * @version V5.1.0 + * @date 09. October 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.6 LTM (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) + #include "cmsis_armclang_ltm.h" + + /* + * Arm Compiler above 6.10.1 (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) + #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 + #define __RESTRICT __restrict + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #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 + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #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 + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +#else + #error Unknown compiler. +#endif + + +#endif /* __CMSIS_COMPILER_H */ + + diff --git a/panda/board/stm32h7/inc/cmsis_gcc.h b/panda/board/stm32h7/inc/cmsis_gcc.h new file mode 100644 index 000000000..2f68473f6 --- /dev/null +++ b/panda/board/stm32h7/inc/cmsis_gcc.h @@ -0,0 +1,2169 @@ +/**************************************************************************//** + * @file cmsis_gcc.h + * @brief CMSIS compiler GCC header file + * @version V5.2.0 + * @date 08. May 2019 + ******************************************************************************/ +/* + * Copyright (c) 2009-2019 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 +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START + +/** + \brief Initializes data and bss sections + \details This default implementations initialized all data and additional bss + sections relying on .copy.table and .zero.table specified properly + in the used linker script. + + */ +__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) +{ + extern void _start(void) __NO_RETURN; + + typedef struct { + uint32_t const* src; + uint32_t* dest; + uint32_t wlen; + } __copy_table_t; + + typedef struct { + uint32_t* dest; + uint32_t wlen; + } __zero_table_t; + + extern const __copy_table_t __copy_table_start__; + extern const __copy_table_t __copy_table_end__; + extern const __zero_table_t __zero_table_start__; + extern const __zero_table_t __zero_table_end__; + + for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = pTable->src[i]; + } + } + + for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = 0u; + } + } + + _start(); +} + +#define __PROGRAM_START __cmsis_start +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP __StackTop +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT __StackLimit +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section(".vectors"))) +#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 + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#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/panda/board/stm32h7/inc/cmsis_version.h b/panda/board/stm32h7/inc/cmsis_version.h new file mode 100644 index 000000000..bf57cf3e8 --- /dev/null +++ b/panda/board/stm32h7/inc/cmsis_version.h @@ -0,0 +1,40 @@ +/**************************************************************************//** + * @file cmsis_version.h + * @brief CMSIS Core(M) Version definitions + * @version V5.0.3 + * @date 24. June 2019 + ******************************************************************************/ +/* + * Copyright (c) 2009-2019 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 ( 3U) /*!< [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/panda/board/stm32h7/inc/core_cm7.h b/panda/board/stm32h7/inc/core_cm7.h new file mode 100644 index 000000000..3da3c43e4 --- /dev/null +++ b/panda/board/stm32h7/inc/core_cm7.h @@ -0,0 +1,2725 @@ +/**************************************************************************//** + * @file core_cm7.h + * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File + * @version V5.1.1 + * @date 28. March 2019 + ******************************************************************************/ +/* + * Copyright (c) 2009-2019 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_CM7_H_GENERIC +#define __CORE_CM7_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_M7 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM7 definitions */ +#define __CM7_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM7_CMSIS_VERSION_SUB ( __CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM7_CMSIS_VERSION ((__CM7_CMSIS_VERSION_MAIN << 16U) | \ + __CM7_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (7U) /*!< 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_FP + #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_CM7_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM7_H_DEPENDANT +#define __CORE_CM7_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM7_REV + #define __CM7_REV 0x0000U + #warning "__CM7_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 __ICACHE_PRESENT + #define __ICACHE_PRESENT 0U + #warning "__ICACHE_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DCACHE_PRESENT + #define __DCACHE_PRESENT 0U + #warning "__DCACHE_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __DTCM_PRESENT + #define __DTCM_PRESENT 0U + #warning "__DTCM_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_M7 */ + + + +/******************************************************************************* + * 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 RESERVED1[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 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_AFR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t ID_MFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ID_ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[1U]; + __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 */ + uint32_t RESERVED3[93U]; + __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_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_BP_Pos 18U /*!< SCB CCR: Branch prediction enable bit Position */ +#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: Branch prediction enable bit Mask */ + +#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: Instruction cache enable bit Position */ +#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: Instruction cache enable bit Mask */ + +#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: Cache enable bit Position */ +#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: Cache enable bit Mask */ + +#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 */ + +/* 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 */ +} 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_DISDYNADD_Pos 26U /*!< ACTLR: DISDYNADD Position */ +#define SCnSCB_ACTLR_DISDYNADD_Msk (1UL << SCnSCB_ACTLR_DISDYNADD_Pos) /*!< ACTLR: DISDYNADD Mask */ + +#define SCnSCB_ACTLR_DISISSCH1_Pos 21U /*!< ACTLR: DISISSCH1 Position */ +#define SCnSCB_ACTLR_DISISSCH1_Msk (0x1FUL << SCnSCB_ACTLR_DISISSCH1_Pos) /*!< ACTLR: DISISSCH1 Mask */ + +#define SCnSCB_ACTLR_DISDI_Pos 16U /*!< ACTLR: DISDI Position */ +#define SCnSCB_ACTLR_DISDI_Msk (0x1FUL << SCnSCB_ACTLR_DISDI_Pos) /*!< ACTLR: DISDI Mask */ + +#define SCnSCB_ACTLR_DISCRITAXIRUR_Pos 15U /*!< ACTLR: DISCRITAXIRUR Position */ +#define SCnSCB_ACTLR_DISCRITAXIRUR_Msk (1UL << SCnSCB_ACTLR_DISCRITAXIRUR_Pos) /*!< ACTLR: DISCRITAXIRUR Mask */ + +#define SCnSCB_ACTLR_DISBTACALLOC_Pos 14U /*!< ACTLR: DISBTACALLOC Position */ +#define SCnSCB_ACTLR_DISBTACALLOC_Msk (1UL << SCnSCB_ACTLR_DISBTACALLOC_Pos) /*!< ACTLR: DISBTACALLOC Mask */ + +#define SCnSCB_ACTLR_DISBTACREAD_Pos 13U /*!< ACTLR: DISBTACREAD Position */ +#define SCnSCB_ACTLR_DISBTACREAD_Msk (1UL << SCnSCB_ACTLR_DISBTACREAD_Pos) /*!< ACTLR: DISBTACREAD Mask */ + +#define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12U /*!< ACTLR: DISITMATBFLUSH Position */ +#define SCnSCB_ACTLR_DISITMATBFLUSH_Msk (1UL << SCnSCB_ACTLR_DISITMATBFLUSH_Pos) /*!< ACTLR: DISITMATBFLUSH Mask */ + +#define SCnSCB_ACTLR_DISRAMODE_Pos 11U /*!< ACTLR: DISRAMODE Position */ +#define SCnSCB_ACTLR_DISRAMODE_Msk (1UL << SCnSCB_ACTLR_DISRAMODE_Pos) /*!< ACTLR: DISRAMODE Mask */ + +#define SCnSCB_ACTLR_FPEXCODIS_Pos 10U /*!< ACTLR: FPEXCODIS Position */ +#define SCnSCB_ACTLR_FPEXCODIS_Msk (1UL << SCnSCB_ACTLR_FPEXCODIS_Pos) /*!< ACTLR: FPEXCODIS 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_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[32U]; + 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 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 */ + uint32_t RESERVED3[981U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( W) Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status 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_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 (0x1UL << 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 (0x1UL << 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 (0x1UL << 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 (0x1UL << 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 */ + __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ +} 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 */ + +/* Media and FP Feature Register 2 Definitions */ + +#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ +#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc 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) + { + __COMPILER_BARRIER(); + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __COMPILER_BARRIER(); + } +} + + +/** + \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->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->IP[((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; + (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; + __DSB(); +} + + +/** + \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 (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); +} + + +/** + \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 = SCB->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 */ + + + +/* ########################## Cache functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_CacheFunctions Cache Functions + \brief Functions that configure Instruction and Data cache. + @{ + */ + +/* Cache Size ID Register Macros */ +#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) +#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) + +#define __SCB_DCACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ +#define __SCB_ICACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ + +/** + \brief Enable I-Cache + \details Turns on I-Cache + */ +__STATIC_FORCEINLINE void SCB_EnableICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + if (SCB->CCR & SCB_CCR_IC_Msk) return; /* return if ICache is already enabled */ + + __DSB(); + __ISB(); + SCB->ICIALLU = 0UL; /* invalidate I-Cache */ + __DSB(); + __ISB(); + SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */ + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Disable I-Cache + \details Turns off I-Cache + */ +__STATIC_FORCEINLINE void SCB_DisableICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + __DSB(); + __ISB(); + SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */ + SCB->ICIALLU = 0UL; /* invalidate I-Cache */ + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Invalidate I-Cache + \details Invalidates I-Cache + */ +__STATIC_FORCEINLINE void SCB_InvalidateICache (void) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + __DSB(); + __ISB(); + SCB->ICIALLU = 0UL; + __DSB(); + __ISB(); + #endif +} + + +/** + \brief I-Cache Invalidate by address + \details Invalidates I-Cache for the given address. + I-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. + I-Cache memory blocks which are part of given address + given size are invalidated. + \param[in] addr address + \param[in] isize size of memory block (in number of bytes) +*/ +__STATIC_FORCEINLINE void SCB_InvalidateICache_by_Addr (void *addr, int32_t isize) +{ + #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) + if ( isize > 0 ) { + int32_t op_size = isize + (((uint32_t)addr) & (__SCB_ICACHE_LINE_SIZE - 1U)); + uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_ICACHE_LINE_SIZE - 1U) */; + + __DSB(); + + do { + SCB->ICIMVAU = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ + op_addr += __SCB_ICACHE_LINE_SIZE; + op_size -= __SCB_ICACHE_LINE_SIZE; + } while ( op_size > 0 ); + + __DSB(); + __ISB(); + } + #endif +} + + +/** + \brief Enable D-Cache + \details Turns on D-Cache + */ +__STATIC_FORCEINLINE void SCB_EnableDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + if (SCB->CCR & SCB_CCR_DC_Msk) return; /* return if DCache is already enabled */ + + SCB->CSSELR = 0U; /* select Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | + ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + __DSB(); + + SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */ + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Disable D-Cache + \details Turns off D-Cache + */ +__STATIC_FORCEINLINE void SCB_DisableDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /* select Level 1 data cache */ + __DSB(); + + SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean & invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | + ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Invalidate D-Cache + \details Invalidates D-Cache + */ +__STATIC_FORCEINLINE void SCB_InvalidateDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /* select Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | + ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Clean D-Cache + \details Cleans D-Cache + */ +__STATIC_FORCEINLINE void SCB_CleanDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /* select Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) | + ((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief Clean & Invalidate D-Cache + \details Cleans and Invalidates D-Cache + */ +__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache (void) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + uint32_t ccsidr; + uint32_t sets; + uint32_t ways; + + SCB->CSSELR = 0U; /* select Level 1 data cache */ + __DSB(); + + ccsidr = SCB->CCSIDR; + + /* clean & invalidate D-Cache */ + sets = (uint32_t)(CCSIDR_SETS(ccsidr)); + do { + ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); + do { + SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | + ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); + #if defined ( __CC_ARM ) + __schedule_barrier(); + #endif + } while (ways-- != 0U); + } while(sets-- != 0U); + + __DSB(); + __ISB(); + #endif +} + + +/** + \brief D-Cache Invalidate by address + \details Invalidates D-Cache for the given address. + D-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. + D-Cache memory blocks which are part of given address + given size are invalidated. + \param[in] addr address + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_FORCEINLINE void SCB_InvalidateDCache_by_Addr (void *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + if ( dsize > 0 ) { + int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); + uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; + + __DSB(); + + do { + SCB->DCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ + op_addr += __SCB_DCACHE_LINE_SIZE; + op_size -= __SCB_DCACHE_LINE_SIZE; + } while ( op_size > 0 ); + + __DSB(); + __ISB(); + } + #endif +} + + +/** + \brief D-Cache Clean by address + \details Cleans D-Cache for the given address + D-Cache is cleaned starting from a 32 byte aligned address in 32 byte granularity. + D-Cache memory blocks which are part of given address + given size are cleaned. + \param[in] addr address + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_FORCEINLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + if ( dsize > 0 ) { + int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); + uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; + + __DSB(); + + do { + SCB->DCCMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ + op_addr += __SCB_DCACHE_LINE_SIZE; + op_size -= __SCB_DCACHE_LINE_SIZE; + } while ( op_size > 0 ); + + __DSB(); + __ISB(); + } + #endif +} + + +/** + \brief D-Cache Clean and Invalidate by address + \details Cleans and invalidates D_Cache for the given address + D-Cache is cleaned and invalidated starting from a 32 byte aligned address in 32 byte granularity. + D-Cache memory blocks which are part of given address + given size are cleaned and invalidated. + \param[in] addr address (aligned to 32-byte boundary) + \param[in] dsize size of memory block (in number of bytes) +*/ +__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) +{ + #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) + if ( dsize > 0 ) { + int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); + uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; + + __DSB(); + + do { + SCB->DCCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ + op_addr += __SCB_DCACHE_LINE_SIZE; + op_size -= __SCB_DCACHE_LINE_SIZE; + } while ( op_size > 0 ); + + __DSB(); + __ISB(); + } + #endif +} + +/*@} end of CMSIS_Core_CacheFunctions */ + + + +/* ################################## 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_CM7_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/panda/board/stm32h7/inc/mpu_armv8.h b/panda/board/stm32h7/inc/mpu_armv8.h new file mode 100644 index 000000000..2fe28b687 --- /dev/null +++ b/panda/board/stm32h7/inc/mpu_armv8.h @@ -0,0 +1,346 @@ +/****************************************************************************** + * @file mpu_armv8.h + * @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU + * @version V5.1.0 + * @date 08. March 2019 + ******************************************************************************/ +/* + * Copyright (c) 2017-2019 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)) + +#if defined(MPU_RLAR_PXN_Pos) + +/** \brief Region Limit Address Register with PXN value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \ + ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ + ((PXN << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \ + ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +#endif + +/** +* 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) +{ + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DMB(); +#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) +{ + MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the Non-secure MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable_NS(void) +{ + __DMB(); +#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 ARM_MPU_OrderedMemcpy(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; + ARM_MPU_OrderedMemcpy(&(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; + ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); + table += c; + cnt -= c; + rnrOffset = 0U; + rnrBase += MPU_TYPE_RALIASES; + mpu->RNR = rnrBase; + } + + ARM_MPU_OrderedMemcpy(&(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/panda/board/stm32h7/inc/stm32h725xx.h b/panda/board/stm32h7/inc/stm32h725xx.h new file mode 100644 index 000000000..0631daac0 --- /dev/null +++ b/panda/board/stm32h7/inc/stm32h725xx.h @@ -0,0 +1,24740 @@ +/** + ****************************************************************************** + * @file stm32h735xx.h + * @author MCD Application Team + * @brief CMSIS STM32H735xx Device Peripheral Access Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral's registers hardware + * + ****************************************************************************** + * @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 + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS_Device + * @{ + */ + +/** @addtogroup stm32h735xx + * @{ + */ + +#ifndef STM32H735xx_H +#define STM32H735xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32H7XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ + PVD_AVD_IRQn = 1, /*!< PVD/AVD 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 and ADC2 global Interrupts */ + FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ + FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ + FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ + FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation 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 */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FMC_IRQn = 48, /*!< FMC global Interrupt */ + SDMMC1_IRQn = 49, /*!< SDMMC1 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 */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ + CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ + HASH_RNG_IRQn = 80, /*!< HASH and 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 */ + SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ + SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ + LTDC_IRQn = 88, /*!< LTDC global Interrupt */ + LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ + DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ + OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ + LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ + CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ + I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ + I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ + SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ + DMAMUX1_OVR_IRQn = 102, /*! + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ + __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ + __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ + __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ + __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ + __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ + __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x02C */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ + __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ + uint32_t RESERVED3; /*!< Reserved, 0x044 */ + uint32_t RESERVED4; /*!< Reserved, 0x048 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ + uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ + __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ + __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ + __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ + __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ + uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ + uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ + __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ + __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ + uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ + uint32_t RESERVED9; /*!< Reserved, 0x0AC */ + __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ + __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ + __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ + __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ + __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ + __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ + __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ +} ADC_TypeDef; + + +typedef struct +{ +__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ +uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ +__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ +__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ +__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ + +} ADC_Common_TypeDef; + + +/** + * @brief VREFBUF + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ + __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ +} VREFBUF_TypeDef; + + +/** + * @brief FD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ + __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ + __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ + __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ + __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ + __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ + __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ + __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ + __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ + __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ + __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ + __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ + __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ + __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ + __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ + __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ + __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ + __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ + __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ + __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ + __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ + __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ + __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ + __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ + __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ + __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ + __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ + __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ + __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ + __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ + __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ + __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ + __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ + __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ + __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ + __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ + __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ + __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ + __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ + __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ + __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ + __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ + __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ + __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ + __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ + __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ + __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ + __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ + __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ + __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ + __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ + __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ + __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ +} FDCAN_GlobalTypeDef; + +/** + * @brief TTFD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ + __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ + __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ + __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ + __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ + __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ + __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ + __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ + __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ + __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ + __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ + __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ + __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ + __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ + __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ + __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ + __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ + __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ + __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ +} TTCAN_TypeDef; + +/** + * @brief FD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ + __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ + __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ + __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ + __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ + __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ +} FDCAN_ClockCalibrationUnit_TypeDef; + + +/** + * @brief Consumer Electronics Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ + __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ + __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ + __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ + __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ + __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ +}CEC_TypeDef; + +/** + * @brief COordincate Rotation DIgital Computer + */ +typedef struct +{ + __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ + __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ + __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ +} CORDIC_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +} CRC_TypeDef; + + +/** + * @brief Clock Recovery System + */ +typedef struct +{ +__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ +__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ +__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ +__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ +} CRS_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 */ + __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ + __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ + __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ + __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ + __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ + __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ +} DAC_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 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 */ + uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ + __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ + uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ + __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ + __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ + __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ + uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ + __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ + __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ + __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ + __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ + __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ + __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ + __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ + __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ + __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ + __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ + __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ + __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ +}DBGMCU_TypeDef; +/** + * @brief DCMI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ + __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ + __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ + __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ + __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ + __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ + __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ + __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ + __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ + __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ + __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ +} DCMI_TypeDef; + +/** + * @brief PSSI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ + __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ + __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ + __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ + __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ + __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ + __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ + __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ + __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ + __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ + __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ + __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ + __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ +} PSSI_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; + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ + __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ +} BDMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +} BDMA_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ +}DMAMUX_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< DMA Channel Status Register */ + __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ +}DMAMUX_ChannelStatus_TypeDef; + +typedef struct +{ + __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ +}DMAMUX_RequestGen_TypeDef; + +typedef struct +{ + __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ + __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ +}DMAMUX_RequestGenStatus_TypeDef; + +/** + * @brief MDMA Controller + */ +typedef struct +{ + __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ +}MDMA_TypeDef; + +typedef struct +{ + __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ + __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ + __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ + __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ + __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ + __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ + __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ + __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ + __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ + __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ + __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ + uint32_t RESERVED0; /*!< Reserved, 0x6C */ + __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ + __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ +}MDMA_Channel_TypeDef; + +/** + * @brief DMA2D Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ + __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ + __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ + __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ + __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ + __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ + __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ + __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ + __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ + __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ + __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ + __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ + __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ + __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ + __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ + __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ + __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ + __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ + __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ + __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ + uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ + __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ + __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ +} DMA2D_TypeDef; + + +/** + * @brief Ethernet MAC + */ +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACECR; + __IO uint32_t MACPFR; + __IO uint32_t MACWTR; + __IO uint32_t MACHT0R; + __IO uint32_t MACHT1R; + uint32_t RESERVED1[14]; + __IO uint32_t MACVTR; + uint32_t RESERVED2; + __IO uint32_t MACVHTR; + uint32_t RESERVED3; + __IO uint32_t MACVIR; + __IO uint32_t MACIVIR; + uint32_t RESERVED4[2]; + __IO uint32_t MACTFCR; + uint32_t RESERVED5[7]; + __IO uint32_t MACRFCR; + uint32_t RESERVED6[7]; + __IO uint32_t MACISR; + __IO uint32_t MACIER; + __IO uint32_t MACRXTXSR; + uint32_t RESERVED7; + __IO uint32_t MACPCSR; + __IO uint32_t MACRWKPFR; + uint32_t RESERVED8[2]; + __IO uint32_t MACLCSR; + __IO uint32_t MACLTCR; + __IO uint32_t MACLETR; + __IO uint32_t MAC1USTCR; + uint32_t RESERVED9[12]; + __IO uint32_t MACVR; + __IO uint32_t MACDR; + uint32_t RESERVED10; + __IO uint32_t MACHWF0R; + __IO uint32_t MACHWF1R; + __IO uint32_t MACHWF2R; + uint32_t RESERVED11[54]; + __IO uint32_t MACMDIOAR; + __IO uint32_t MACMDIODR; + uint32_t RESERVED12[2]; + __IO uint32_t MACARPAR; + uint32_t RESERVED13[59]; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; + uint32_t RESERVED14[248]; + __IO uint32_t MMCCR; + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; + uint32_t RESERVED15[14]; + __IO uint32_t MMCTSCGPR; + __IO uint32_t MMCTMCGPR; + uint32_t RESERVED16[5]; + __IO uint32_t MMCTPCGR; + uint32_t RESERVED17[10]; + __IO uint32_t MMCRCRCEPR; + __IO uint32_t MMCRAEPR; + uint32_t RESERVED18[10]; + __IO uint32_t MMCRUPGR; + uint32_t RESERVED19[9]; + __IO uint32_t MMCTLPIMSTR; + __IO uint32_t MMCTLPITCR; + __IO uint32_t MMCRLPIMSTR; + __IO uint32_t MMCRLPITCR; + uint32_t RESERVED20[65]; + __IO uint32_t MACL3L4C0R; + __IO uint32_t MACL4A0R; + uint32_t RESERVED21[2]; + __IO uint32_t MACL3A0R0R; + __IO uint32_t MACL3A1R0R; + __IO uint32_t MACL3A2R0R; + __IO uint32_t MACL3A3R0R; + uint32_t RESERVED22[4]; + __IO uint32_t MACL3L4C1R; + __IO uint32_t MACL4A1R; + uint32_t RESERVED23[2]; + __IO uint32_t MACL3A0R1R; + __IO uint32_t MACL3A1R1R; + __IO uint32_t MACL3A2R1R; + __IO uint32_t MACL3A3R1R; + uint32_t RESERVED24[108]; + __IO uint32_t MACTSCR; + __IO uint32_t MACSSIR; + __IO uint32_t MACSTSR; + __IO uint32_t MACSTNR; + __IO uint32_t MACSTSUR; + __IO uint32_t MACSTNUR; + __IO uint32_t MACTSAR; + uint32_t RESERVED25; + __IO uint32_t MACTSSR; + uint32_t RESERVED26[3]; + __IO uint32_t MACTTSSNR; + __IO uint32_t MACTTSSSR; + uint32_t RESERVED27[2]; + __IO uint32_t MACACR; + uint32_t RESERVED28; + __IO uint32_t MACATSNR; + __IO uint32_t MACATSSR; + __IO uint32_t MACTSIACR; + __IO uint32_t MACTSEACR; + __IO uint32_t MACTSICNR; + __IO uint32_t MACTSECNR; + uint32_t RESERVED29[4]; + __IO uint32_t MACPPSCR; + uint32_t RESERVED30[3]; + __IO uint32_t MACPPSTTSR; + __IO uint32_t MACPPSTTNR; + __IO uint32_t MACPPSIR; + __IO uint32_t MACPPSWR; + uint32_t RESERVED31[12]; + __IO uint32_t MACPOCR; + __IO uint32_t MACSPI0R; + __IO uint32_t MACSPI1R; + __IO uint32_t MACSPI2R; + __IO uint32_t MACLMIR; + uint32_t RESERVED32[11]; + __IO uint32_t MTLOMR; + uint32_t RESERVED33[7]; + __IO uint32_t MTLISR; + uint32_t RESERVED34[55]; + __IO uint32_t MTLTQOMR; + __IO uint32_t MTLTQUR; + __IO uint32_t MTLTQDR; + uint32_t RESERVED35[8]; + __IO uint32_t MTLQICSR; + __IO uint32_t MTLRQOMR; + __IO uint32_t MTLRQMPOCR; + __IO uint32_t MTLRQDR; + uint32_t RESERVED36[177]; + __IO uint32_t DMAMR; + __IO uint32_t DMASBMR; + __IO uint32_t DMAISR; + __IO uint32_t DMADSR; + uint32_t RESERVED37[60]; + __IO uint32_t DMACCR; + __IO uint32_t DMACTCR; + __IO uint32_t DMACRCR; + uint32_t RESERVED38[2]; + __IO uint32_t DMACTDLAR; + uint32_t RESERVED39; + __IO uint32_t DMACRDLAR; + __IO uint32_t DMACTDTPR; + uint32_t RESERVED40; + __IO uint32_t DMACRDTPR; + __IO uint32_t DMACTDRLR; + __IO uint32_t DMACRDRLR; + __IO uint32_t DMACIER; + __IO uint32_t DMACRIWTR; +__IO uint32_t DMACSFCSR; + uint32_t RESERVED41; + __IO uint32_t DMACCATDR; + uint32_t RESERVED42; + __IO uint32_t DMACCARDR; + uint32_t RESERVED43; + __IO uint32_t DMACCATBR; + uint32_t RESERVED44; + __IO uint32_t DMACCARBR; + __IO uint32_t DMACSR; +uint32_t RESERVED45[2]; +__IO uint32_t DMACMFCR; +}ETH_TypeDef; +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ +__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ +__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ +__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ +__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ +__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ +__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ +uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ +__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ +__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ +__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ +__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ +__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ +__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ +uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ +__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ +__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ +__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ +__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ +__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ +__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ +uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ +__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ +__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ +__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ +uint32_t RESERVED4; /*!< Reserved, 0x8C */ +__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ +__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ +__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ +uint32_t RESERVED5; /*!< Reserved, 0x9C */ +__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ +__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ +__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ +}EXTI_TypeDef; + +/** + * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 + * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. + * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: + * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) + * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) + * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only + */ + +typedef struct +{ +__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ +__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ +__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ +uint32_t RESERVED1; /*!< Reserved, 0x0C */ +__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ +__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ +__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ +uint32_t RESERVED2; /*!< Reserved, 0x1C */ +__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ +__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ +__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ +}EXTI_Core_TypeDef; + + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ + __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ + __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ + __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ + __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ + __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ + __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ + __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ + __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ + __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ + __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ + __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ + __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ + __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ + __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ + __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ + __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ + __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ + __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ + __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ + uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ + __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ + __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ +} FLASH_TypeDef; + +/** + * @brief Filter and Mathematical ACcelerator + */ +typedef struct +{ + __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ + __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ + __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ + __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ + __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ + __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ +} FMAC_TypeDef; + +/** + * @brief Flexible 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 */ +} FMC_Bank1_TypeDef; + +/** + * @brief Flexible Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FMC_Bank1E_TypeDef; + +/** + * @brief Flexible Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ +} FMC_Bank2_TypeDef; + +/** + * @brief Flexible Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FMC_Bank3_TypeDef; + +/** + * @brief Flexible Memory Controller Bank5 and 6 + */ + + +typedef struct +{ + __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ + __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ + __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ + __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ + __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ +} FMC_Bank5_6_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, 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 Operational Amplifier (OPAMP) + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ + __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ + __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ +} OPAMP_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ + __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ + __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ + __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ + __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ + __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ + uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ + __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ + uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ + __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ + __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ + __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ + __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ + __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ + __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ + __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ + __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ + uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ + __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ + __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ + __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ + __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ + __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ + __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ + __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ + __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ + +} 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 1 register, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ + __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ + __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ + __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ + __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ + __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ + __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ + __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ + __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ +} IWDG_TypeDef; + + +/** + * @brief LCD-TFT Display Controller + */ + +typedef struct +{ + uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ + __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ + __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ + __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ + __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ + __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ + __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ + uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ + __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ + uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ + __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ + __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ + __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ + __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ + __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ + __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ +} LTDC_TypeDef; + +/** + * @brief LCD-TFT Display layer x Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ + __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ + __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ + __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ + __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ + __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ + __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ + __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ + uint32_t RESERVED0[2]; /*!< Reserved */ + __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ + __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ + __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ + uint32_t RESERVED1[3]; /*!< Reserved */ + __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ + +} LTDC_Layer_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ + __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ + __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ + __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ + uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ + __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ + __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ + __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ + __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ + __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ + __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ + __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ + __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ + __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ + __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ + __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ + __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ + __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ + __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ + __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ + __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ + __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ + __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ + __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ + __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ + __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ + __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ + __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ + __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ + uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ + __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ + __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ + __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ + __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ + __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ + __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ + __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ + uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ + __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ + uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ + __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ + __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ + __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ + __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ + __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ + __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ + uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ + __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ + __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ + __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ + __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ + __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ + uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ + +} 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 */ + uint32_t RESERVED; /*!< Reserved, 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 TAMPCR; /*!< RTC tamper 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 */ + __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 0, 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 */ + __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ + __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ + __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ + __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ + __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ + __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ + __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ + __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ + __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ + __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ + __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ + __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ +} RTC_TypeDef; + +/** + * @brief Serial Audio Interface + */ + +typedef struct +{ + __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ + uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ + __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ + __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ +} 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 SPDIF-RX Interface + */ + +typedef struct +{ + __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ + __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ + __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ + __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ + __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ + __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1A */ +} SPDIFRX_TypeDef; + + +/** + * @brief Secure digital input/output Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ + __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ + __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ + __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ + __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ + __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ + __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ + __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ + __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ + uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ + __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ + __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ + __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ + __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ + uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ + __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ + uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ + __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ +} SDMMC_TypeDef; + + +/** + * @brief Delay Block DLYB + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ + __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ +} DLYB_TypeDef; + +/** + * @brief HW Semaphore HSEM + */ + +typedef struct +{ + __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ + __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ + __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ + __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ + __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ + __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ + uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ + __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ + __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ + +} HSEM_TypeDef; + +typedef struct +{ + __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ + __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ + __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ + __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ +} HSEM_Common_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ + __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ + __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ + __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ + __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ + uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ + __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ + uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ + __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ + __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ + __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ + __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ + __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ + +} SPI_TypeDef; + +/** + * @brief DTS + */ +typedef struct +{ + __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ + uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ + __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ + __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ + __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ + __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ + __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ + __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ + __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ + __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ +} +DTS_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 */ + uint32_t RESERVED1; /*!< Reserved, 0x50 */ + __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ + __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ + __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ + __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ + __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ + __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ +} TIM_TypeDef; + +/** + * @brief LPTIMIMER + */ +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 */ + uint32_t RESERVED1; /*!< Reserved, 0x20 */ + __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ +} LPTIM_TypeDef; + +/** + * @brief Comparator + */ +typedef struct +{ + __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ + __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ + __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ +} COMPOPT_TypeDef; + +typedef struct +{ + __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ +} COMP_TypeDef; + +typedef struct +{ + __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ +} COMP_Common_TypeDef; +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ + __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ + __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ + __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ + __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ + __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ + __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ + __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ +} USART_TypeDef; + +/** + * @brief Single Wire Protocol Master Interface SPWMI + */ +typedef struct +{ + __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ + __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ + uint32_t RESERVED1; /*!< Reserved, 0x08 */ + __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ + __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ + __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ + __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ + __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ + __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ +} SWPMI_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 RAM_ECC_Specific_Registers + */ +typedef struct +{ + __IO uint32_t CR; /*!< RAMECC monitor configuration register */ + __IO uint32_t SR; /*!< RAMECC monitor status register */ + __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ + __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ + __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ + __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ +} RAMECC_MonitorTypeDef; + +typedef struct +{ + __IO uint32_t IER; /*!< RAMECC interrupt enable register */ +} RAMECC_TypeDef; +/** + * @} + */ + + +/** + * @brief Crypto Processor + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ + __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ + __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ + __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ + __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ + __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ + __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ + __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ + __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ + __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ + __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ + __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ + __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ + __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ + __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ + __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ + __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ + __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ + __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ + __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ + __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ + __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ + __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ + __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ + __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ + __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ + __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ + __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ + __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ + __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ + __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ + __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ + __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ + __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ + __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ +} CRYP_TypeDef; + +/** + * @brief HASH + */ + +typedef struct +{ + __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ + __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ + __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ + __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ + __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ + __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ + uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ + __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ +} HASH_TypeDef; + +/** + * @brief HASH_DIGEST + */ + +typedef struct +{ + __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ +} HASH_DIGEST_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 */ + uint32_t RESERVED; + __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ +} RNG_TypeDef; + +/** + * @brief MDIOS + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t WRFR; + __IO uint32_t CWRFR; + __IO uint32_t RDFR; + __IO uint32_t CRDFR; + __IO uint32_t SR; + __IO uint32_t CLRFR; + uint32_t RESERVED[57]; + __IO uint32_t DINR0; + __IO uint32_t DINR1; + __IO uint32_t DINR2; + __IO uint32_t DINR3; + __IO uint32_t DINR4; + __IO uint32_t DINR5; + __IO uint32_t DINR6; + __IO uint32_t DINR7; + __IO uint32_t DINR8; + __IO uint32_t DINR9; + __IO uint32_t DINR10; + __IO uint32_t DINR11; + __IO uint32_t DINR12; + __IO uint32_t DINR13; + __IO uint32_t DINR14; + __IO uint32_t DINR15; + __IO uint32_t DINR16; + __IO uint32_t DINR17; + __IO uint32_t DINR18; + __IO uint32_t DINR19; + __IO uint32_t DINR20; + __IO uint32_t DINR21; + __IO uint32_t DINR22; + __IO uint32_t DINR23; + __IO uint32_t DINR24; + __IO uint32_t DINR25; + __IO uint32_t DINR26; + __IO uint32_t DINR27; + __IO uint32_t DINR28; + __IO uint32_t DINR29; + __IO uint32_t DINR30; + __IO uint32_t DINR31; + __IO uint32_t DOUTR0; + __IO uint32_t DOUTR1; + __IO uint32_t DOUTR2; + __IO uint32_t DOUTR3; + __IO uint32_t DOUTR4; + __IO uint32_t DOUTR5; + __IO uint32_t DOUTR6; + __IO uint32_t DOUTR7; + __IO uint32_t DOUTR8; + __IO uint32_t DOUTR9; + __IO uint32_t DOUTR10; + __IO uint32_t DOUTR11; + __IO uint32_t DOUTR12; + __IO uint32_t DOUTR13; + __IO uint32_t DOUTR14; + __IO uint32_t DOUTR15; + __IO uint32_t DOUTR16; + __IO uint32_t DOUTR17; + __IO uint32_t DOUTR18; + __IO uint32_t DOUTR19; + __IO uint32_t DOUTR20; + __IO uint32_t DOUTR21; + __IO uint32_t DOUTR22; + __IO uint32_t DOUTR23; + __IO uint32_t DOUTR24; + __IO uint32_t DOUTR25; + __IO uint32_t DOUTR26; + __IO uint32_t DOUTR27; + __IO uint32_t DOUTR28; + __IO uint32_t DOUTR29; + __IO uint32_t DOUTR30; + __IO uint32_t DOUTR31; +} MDIOS_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 */ + __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ + __IO uint32_t GHWCFG1; /* User HW config1 044h*/ + __IO uint32_t GHWCFG2; /* User HW config2 048h*/ + __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ + uint32_t Reserved6; /*!< Reserved 050h */ + __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ + __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ + __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ + __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ + uint32_t Reserved43[39]; /*!< 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 OCTO Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ + uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ + __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ + __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ + __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ + __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ + uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ + __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ + __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ + uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ + __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ + __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ + uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ + __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ + uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ + __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ + __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ + __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ + uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ + __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ + uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ + __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ + uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ + __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ + uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ + __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ + uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ + __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ + uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ + __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ + uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ + __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ + uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ + __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ + uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ + __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ + uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ + __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ + uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ + __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ + uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ + __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ + uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ + __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ + uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ + __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ + uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ + __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ + __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ + __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ + __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ +} OCTOSPI_TypeDef; + +/** + * @} + */ +/** + * @brief OCTO Serial Peripheral Interface IO Manager + */ + +typedef struct +{ + __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ + __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ +} OCTOSPIM_TypeDef; + +/** + * @} + */ + +/** + * @brief OTFD register + */ +typedef struct +{ + __IO uint32_t REG_CONFIGR; + __IO uint32_t REG_START_ADDR; + __IO uint32_t REG_END_ADDR; + __IO uint32_t REG_NONCER0; + __IO uint32_t REG_NONCER1; + __IO uint32_t REG_KEYR0; + __IO uint32_t REG_KEYR1; + __IO uint32_t REG_KEYR2; + __IO uint32_t REG_KEYR3; +} OTFDEC_Region_TypeDef; + +typedef struct +{ + __IO uint32_t CR; + uint32_t RESERVED1[191]; + __IO uint32_t ISR; + __IO uint32_t ICR; + __IO uint32_t IER; + uint32_t RESERVED2[56]; + __IO uint32_t HWCFGR2; + __IO uint32_t HWCFGR1; + __IO uint32_t VERR; + __IO uint32_t IPIDR; + __IO uint32_t SIDR; +} OTFDEC_TypeDef; +/** + * @} + */ + +/** + * @brief Global Programmer View + */ + +typedef struct +{ + uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ + __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ + uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ + uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ + uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ + __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ + __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ + __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ + __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ + __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ + __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ + __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ + __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ + uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ + __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ + uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ + __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ + __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ + uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ + __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ + uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ + __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ + uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ + __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ + __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ + uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ + __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ + uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ + __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ + uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ + __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ + uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ + __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ + uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ + __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ + uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ + __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ + uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ + __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ + uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ + __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ + uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ + __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ + uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ + __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ + uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ + __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ + uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ + __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ + uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ + __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ + __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ + uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ + __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ + __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ + __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ + uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ + __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ + __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ + __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ + uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ + __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ + __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ + uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ + __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ + __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ + __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ + uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ + __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ + __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ + __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ + uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ + __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ + __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ + __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ + uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ + __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ + __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ + __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ + +} GPV_TypeDef; + +/** @addtogroup Peripheral_memory_map + * @{ + */ +#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ +#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ +#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ +#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ +#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ +#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ +#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ +#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ + +#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ +#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ +#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ + +#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ +#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ + +#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ +#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ +#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ + +#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ +#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ + + +/* Legacy define */ +#define FLASH_BASE FLASH_BANK1_BASE + +/*!< Device electronic signature memory map */ +#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ +#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ + + +/*!< Peripheral memory map */ +#define D2_APB1PERIPH_BASE PERIPH_BASE +#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) +#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) +#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) + +#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) +#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) + +#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) +#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) + +/*!< Legacy 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 + 0x08000000UL) + + +/*!< D1_AHB1PERIPH peripherals */ + +#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) +#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) +#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) +#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) +#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) +#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) +#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) +#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) +#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) +#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) +#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) +#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) + +#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) +#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) +#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) +#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) +#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) +#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) +#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) +#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) +#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) +#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) + +/*!< D2_AHB1PERIPH peripherals */ + +#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) +#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) +#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) +#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) +#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) +#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) +#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) +#define ETH_MAC_BASE (ETH_BASE) + +/*!< USB registers base address */ +#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) +#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) + +/*!< D2_AHB2PERIPH peripherals */ + +#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) +#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) +#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) +#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) +#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) +#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) +#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) +#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) +#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) +#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) +#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) + +/*!< D3_AHB1PERIPH peripherals */ +#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) +#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) +#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) +#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) +#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) +#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) +#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) +#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) +#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) +#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) +#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) +#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) +#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) +#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) +#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) +#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) +#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) +#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) +#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) + +/*!< D1_APB1PERIPH peripherals */ +#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) +#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) +#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) +#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) + +/*!< D2_APB1PERIPH peripherals */ +#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) +#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) +#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) +#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) +#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) +#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) +#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) +#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) +#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) +#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) + + +#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) +#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) +#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) +#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) +#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) +#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) +#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) +#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) +#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) +#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) +#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) +#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) +#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) +#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) +#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) +#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) +#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) +#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) +#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) +#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) +#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) +#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) +#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) +#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) +#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) +#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) +#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) +#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) + +/*!< D2_APB2PERIPH peripherals */ + +#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) +#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) +#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) +#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) +#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) +#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) +#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) +#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) +#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) +#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) +#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) +#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) +#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) +#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) +#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) +#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) +#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_Channel4_BASE (DFSDM1_BASE + 0x80UL) +#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) +#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) +#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) +#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) +#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) +#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) +#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) + + +/*!< D3_APB1PERIPH peripherals */ +#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) +#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) +#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) +#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) +#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) +#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) +#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) +#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) +#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) +#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) +#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) +#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) +#define COMP1_BASE (COMP12_BASE + 0x0CUL) +#define COMP2_BASE (COMP12_BASE + 0x10UL) +#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) +#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) +#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) + + +#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) +#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) +#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) + +#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) + + + +#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) +#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) +#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) +#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) +#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) +#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) +#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) +#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) + +#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) +#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) +#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) +#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) +#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) +#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) +#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) +#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) + +#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) +#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) +#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) +#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) +#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) +#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) +#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) +#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) + +#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) +#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) + +#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_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) + +#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) +#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) +#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) +#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) +#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) +#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) +#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) +#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) +#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) +#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) +#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) +#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) +#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) +#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) +#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) +#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) + +#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) +#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) +#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) +#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) +#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) +#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) +#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) +#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) + +#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) +#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) + +/*!< FMC Banks registers base address */ +#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) +#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) +#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) +#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) +#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE (0x5C001000UL) + +#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) +#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) +#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) +#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) +#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) +#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) +#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) +#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) +#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) +#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) +#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) +#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) +#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) +#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) +#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) +#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) + +#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) +#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) +#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) +#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) +#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) +#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) + +#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) +#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) +#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) + +#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) +#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) + + + +#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ + +/** + * @} + */ + +/** @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 TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) + + +#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define SPI4 ((SPI_TypeDef *) SPI4_BASE) +#define SPI5 ((SPI_TypeDef *) SPI5_BASE) +#define SPI6 ((SPI_TypeDef *) SPI6_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define USART10 ((USART_TypeDef *) USART10_BASE) +#define UART7 ((USART_TypeDef *) UART7_BASE) +#define UART8 ((USART_TypeDef *) UART8_BASE) +#define UART9 ((USART_TypeDef *) UART9_BASE) +#define CRS ((CRS_TypeDef *) CRS_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 I2C4 ((I2C_TypeDef *) I2C4_BASE) +#define I2C5 ((I2C_TypeDef *) I2C5_BASE) +#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) +#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) +#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) +#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) +#define TIM23 ((TIM_TypeDef *) TIM23_BASE) +#define TIM24 ((TIM_TypeDef *) TIM24_BASE) +#define CEC ((CEC_TypeDef *) CEC_BASE) +#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC1 ((DAC_TypeDef *) DAC1_BASE) +#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) +#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) +#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) +#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) +#define DTS ((DTS_TypeDef *) DTS_BASE) +#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) +#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) + +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) +#define COMP1 ((COMP_TypeDef *) COMP1_BASE) +#define COMP2 ((COMP_TypeDef *) COMP2_BASE) +#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) +#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) +#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) +#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) + + +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) +#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_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 SAI4 ((SAI_TypeDef *) SAI4_BASE) +#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) +#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) + +#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_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_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) +#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) +#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) +#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) +#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) +#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) +#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) +#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) +#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) +#define DCMI ((DCMI_TypeDef *) DCMI_BASE) +#define PSSI ((PSSI_TypeDef *) PSSI_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define CRC ((CRC_TypeDef *) CRC_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 GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) +#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) + +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) +#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) + +#define CRYP ((CRYP_TypeDef *) CRYP_BASE) +#define HASH ((HASH_TypeDef *) HASH_BASE) +#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) +#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) +#define FMAC ((FMAC_TypeDef *) FMAC_BASE) +#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) + +#define BDMA ((BDMA_TypeDef *) BDMA_BASE) +#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) +#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) +#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) +#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) +#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) +#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) +#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) +#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) + +#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) +#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) +#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) +#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) +#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) +#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) +#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) + +#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) +#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) +#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) +#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) + +#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) +#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) +#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) + +#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) +#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) +#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) +#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) +#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) +#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) +#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) +#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) +#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) + + +#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) +#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) +#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) +#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) +#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) +#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) +#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) +#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) + +#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) +#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_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 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 DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) +#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) +#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) +#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) +#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) +#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) +#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) +#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) +#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) +#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) +#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) +#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) +#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) +#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) +#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) +#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) +#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) + +#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) +#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) +#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) +#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) +#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) +#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) +#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) +#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) + +#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) +#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) + + +#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) +#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) +#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) +#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) +#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) + +#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) +#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) +#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) +#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) +#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) + +#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) +#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) +#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) +#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) +#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) + +#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) +#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) +#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) +#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) +#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) + +#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) +#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +#define HSEM ((HSEM_TypeDef *) HSEM_BASE) +#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) + +#define LTDC ((LTDC_TypeDef *)LTDC_BASE) +#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) +#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) + +#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) + +#define ETH ((ETH_TypeDef *)ETH_BASE) +#define MDMA ((MDMA_TypeDef *)MDMA_BASE) +#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) +#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) +#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) +#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) +#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) +#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) +#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) +#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) +#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) +#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) +#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) +#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) +#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) +#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) +#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) +#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) + + +#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) + +/* Legacy defines */ +#define USB_OTG_HS USB1_OTG_HS +#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE + +#define GPV ((GPV_TypeDef *) GPV_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************************* ADC VERSION ********************************/ +#define ADC_VER_V5_V90 +/******************** Bit definition for ADC_ISR register ********************/ +#define ADC_ISR_ADRDY_Pos (0U) +#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ +#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ +#define ADC_ISR_EOSMP_Pos (1U) +#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ +#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ +#define ADC_ISR_EOC_Pos (2U) +#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ +#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ +#define ADC_ISR_EOS_Pos (3U) +#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ +#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ +#define ADC_ISR_OVR_Pos (4U) +#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ +#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ +#define ADC_ISR_JEOC_Pos (5U) +#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ +#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ +#define ADC_ISR_JEOS_Pos (6U) +#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ +#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ +#define ADC_ISR_AWD1_Pos (7U) +#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ +#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ +#define ADC_ISR_AWD2_Pos (8U) +#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ +#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ +#define ADC_ISR_AWD3_Pos (9U) +#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ +#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ +#define ADC_ISR_JQOVF_Pos (10U) +#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ +#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ +#define ADC_ISR_LDORDY_Pos (12U) +#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ +#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ + +/******************** Bit definition for ADC_IER register ********************/ +#define ADC_IER_ADRDYIE_Pos (0U) +#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ +#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ +#define ADC_IER_EOSMPIE_Pos (1U) +#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ +#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ +#define ADC_IER_EOCIE_Pos (2U) +#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ +#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ +#define ADC_IER_EOSIE_Pos (3U) +#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ +#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ +#define ADC_IER_OVRIE_Pos (4U) +#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ +#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ +#define ADC_IER_JEOCIE_Pos (5U) +#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ +#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ +#define ADC_IER_JEOSIE_Pos (6U) +#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ +#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ +#define ADC_IER_AWD1IE_Pos (7U) +#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ +#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ +#define ADC_IER_AWD2IE_Pos (8U) +#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ +#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ +#define ADC_IER_AWD3IE_Pos (9U) +#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ +#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ +#define ADC_IER_JQOVFIE_Pos (10U) +#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ +#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ + +/******************** Bit definition for ADC_CR register ********************/ +#define ADC_CR_ADEN_Pos (0U) +#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ +#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ +#define ADC_CR_ADDIS_Pos (1U) +#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ +#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ +#define ADC_CR_ADSTART_Pos (2U) +#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ +#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ +#define ADC_CR_JADSTART_Pos (3U) +#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ +#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ +#define ADC_CR_ADSTP_Pos (4U) +#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ +#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ +#define ADC_CR_JADSTP_Pos (5U) +#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ +#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ +#define ADC_CR_BOOST_Pos (8U) +#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ +#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ +#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ +#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ +#define ADC_CR_ADCALLIN_Pos (16U) +#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ +#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ +#define ADC_CR_LINCALRDYW1_Pos (22U) +#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ +#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ +#define ADC_CR_LINCALRDYW2_Pos (23U) +#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ +#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ +#define ADC_CR_LINCALRDYW3_Pos (24U) +#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ +#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ +#define ADC_CR_LINCALRDYW4_Pos (25U) +#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ +#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ +#define ADC_CR_LINCALRDYW5_Pos (26U) +#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ +#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ +#define ADC_CR_LINCALRDYW6_Pos (27U) +#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ +#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ +#define ADC_CR_ADVREGEN_Pos (28U) +#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ +#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ +#define ADC_CR_DEEPPWD_Pos (29U) +#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ +#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ +#define ADC_CR_ADCALDIF_Pos (30U) +#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ +#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ +#define ADC_CR_ADCAL_Pos (31U) +#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ +#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ + +/******************** Bit definition for ADC_CFGR register ********************/ +#define ADC_CFGR_DMNGT_Pos (0U) +#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ +#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ +#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ +#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ + +#define ADC_CFGR_RES_Pos (2U) +#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ +#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ +#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ +#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ +#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ + +#define ADC_CFGR_EXTSEL_Pos (5U) +#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ +#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ +#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ +#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ +#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ +#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ + +#define ADC_CFGR_EXTEN_Pos (10U) +#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ +#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ +#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ +#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ + +#define ADC_CFGR_OVRMOD_Pos (12U) +#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ +#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ +#define ADC_CFGR_CONT_Pos (13U) +#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ +#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ +#define ADC_CFGR_AUTDLY_Pos (14U) +#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ +#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ + +#define ADC_CFGR_DISCEN_Pos (16U) +#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ +#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ + +#define ADC_CFGR_DISCNUM_Pos (17U) +#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ +#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ +#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ +#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ +#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ + +#define ADC_CFGR_JDISCEN_Pos (20U) +#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ +#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ +#define ADC_CFGR_JQM_Pos (21U) +#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ +#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ +#define ADC_CFGR_AWD1SGL_Pos (22U) +#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ +#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ +#define ADC_CFGR_AWD1EN_Pos (23U) +#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ +#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ +#define ADC_CFGR_JAWD1EN_Pos (24U) +#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ +#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ +#define ADC_CFGR_JAUTO_Pos (25U) +#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ +#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ + +#define ADC_CFGR_AWD1CH_Pos (26U) +#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ +#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ +#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ +#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ +#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ +#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ +#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ + +#define ADC_CFGR_JQDIS_Pos (31U) +#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ +#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ + +#define ADC3_CFGR_DMAEN_Pos (0U) +#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ +#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ +#define ADC3_CFGR_DMACFG_Pos (1U) +#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ +#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ + +#define ADC3_CFGR_RES_Pos (3U) +#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ +#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ +#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ +#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ + +#define ADC3_CFGR_ALIGN_Pos (15U) +#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ +#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ +/******************** Bit definition for ADC_CFGR2 register ********************/ +#define ADC_CFGR2_ROVSE_Pos (0U) +#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ +#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ +#define ADC_CFGR2_JOVSE_Pos (1U) +#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ +#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ + +#define ADC_CFGR2_OVSS_Pos (5U) +#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ +#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ +#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ +#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ +#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ +#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ + +#define ADC_CFGR2_TROVS_Pos (9U) +#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ +#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ +#define ADC_CFGR2_ROVSM_Pos (10U) +#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ +#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ + +#define ADC_CFGR2_RSHIFT1_Pos (11U) +#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ +#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ +#define ADC_CFGR2_RSHIFT2_Pos (12U) +#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ +#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ +#define ADC_CFGR2_RSHIFT3_Pos (13U) +#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ +#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ +#define ADC_CFGR2_RSHIFT4_Pos (14U) +#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ +#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ + +#define ADC_CFGR2_OVSR_Pos (16U) +#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ +#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ +#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ +#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ +#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ +#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ +#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ +#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ +#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ +#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ +#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ +#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ + +#define ADC_CFGR2_LSHIFT_Pos (28U) +#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ +#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ +#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ +#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ +#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ +#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ + +#define ADC3_CFGR2_OVSR_Pos (2U) +#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ +#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ +#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ +#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ +#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ + +#define ADC3_CFGR2_SWTRIG_Pos (25U) +#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ +#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ +#define ADC3_CFGR2_BULB_Pos (26U) +#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ +#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ +#define ADC3_CFGR2_SMPTRIG_Pos (27U) +#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ +#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ +/******************** Bit definition for ADC_SMPR1 register ********************/ +#define ADC_SMPR1_SMP0_Pos (0U) +#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ +#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ +#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ +#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ +#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR1_SMP1_Pos (3U) +#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ +#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ +#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ +#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ +#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR1_SMP2_Pos (6U) +#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ +#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ +#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ +#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR1_SMP3_Pos (9U) +#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ +#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ +#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ +#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR1_SMP4_Pos (12U) +#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ +#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ +#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ +#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ +#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR1_SMP5_Pos (15U) +#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ +#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ +#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ +#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ +#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR1_SMP6_Pos (18U) +#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ +#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ +#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ +#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR1_SMP7_Pos (21U) +#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ +#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ +#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ +#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR1_SMP8_Pos (24U) +#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ +#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ +#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ +#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ +#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ + +#define ADC_SMPR1_SMP9_Pos (27U) +#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ +#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ +#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ +#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ +#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ + +/******************** Bit definition for ADC_SMPR2 register ********************/ +#define ADC_SMPR2_SMP10_Pos (0U) +#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ +#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ +#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ +#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ +#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR2_SMP11_Pos (3U) +#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ +#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ +#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ +#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ +#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR2_SMP12_Pos (6U) +#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ +#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ +#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ +#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR2_SMP13_Pos (9U) +#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ +#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ +#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ +#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR2_SMP14_Pos (12U) +#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ +#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ +#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ +#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ +#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR2_SMP15_Pos (15U) +#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ +#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ +#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ +#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ +#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR2_SMP16_Pos (18U) +#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ +#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ +#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ +#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR2_SMP17_Pos (21U) +#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ +#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ +#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ +#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR2_SMP18_Pos (24U) +#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ +#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ +#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ +#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ +#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ + +#define ADC_SMPR2_SMP19_Pos (27U) +#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ +#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ +#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ +#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ +#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ + +/******************** Bit definition for ADC_PCSEL register ********************/ +#define ADC_PCSEL_PCSEL_Pos (0U) +#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ +#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ +#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ +#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ +#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ +#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ +#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ +#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ +#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ +#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ +#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ +#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ +#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ +#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ +#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ +#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ +#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ +#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ +#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ +#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ +#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ +#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ + +/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ +#define ADC_LTR_LT_Pos (0U) +#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ +#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ + +/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ +#define ADC_HTR_HT_Pos (0U) +#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ +#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ + +/******************** Bit definition for ADC3_TR1 register *******************/ +#define ADC3_TR1_LT1_Pos (0U) +#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ +#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ + +#define ADC3_TR1_AWDFILT_Pos (12U) +#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ +#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ +#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ +#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ +#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ + +#define ADC3_TR1_HT1_Pos (16U) +#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ +#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ + +/******************** Bit definition for ADC3_TR2 register *******************/ +#define ADC3_TR2_LT2_Pos (0U) +#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ +#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ + +#define ADC3_TR2_HT2_Pos (16U) +#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ +#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ + +/******************** Bit definition for ADC3_TR3 register *******************/ +#define ADC3_TR3_LT3_Pos (0U) +#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ +#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ + +#define ADC3_TR3_HT3_Pos (16U) +#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ +#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ + +/******************** Bit definition for ADC_SQR1 register ********************/ +#define ADC_SQR1_L_Pos (0U) +#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ +#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ +#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ +#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ +#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ +#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ + +#define ADC_SQR1_SQ1_Pos (6U) +#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ +#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ +#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ +#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ +#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ +#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ +#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ + +#define ADC_SQR1_SQ2_Pos (12U) +#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ +#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ +#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ +#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ +#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ +#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ +#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ + +#define ADC_SQR1_SQ3_Pos (18U) +#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ +#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ +#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ +#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ +#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ +#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ +#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ + +#define ADC_SQR1_SQ4_Pos (24U) +#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ +#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ +#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ +#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ +#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ +#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ +#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR2 register ********************/ +#define ADC_SQR2_SQ5_Pos (0U) +#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ +#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ +#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ +#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ +#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ +#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ +#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ + +#define ADC_SQR2_SQ6_Pos (6U) +#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ +#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ +#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ +#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ +#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ +#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ +#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ + +#define ADC_SQR2_SQ7_Pos (12U) +#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ +#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ +#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ +#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ +#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ +#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ +#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ + +#define ADC_SQR2_SQ8_Pos (18U) +#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ +#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ +#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ +#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ +#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ +#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ +#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ + +#define ADC_SQR2_SQ9_Pos (24U) +#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ +#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ +#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ +#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ +#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ +#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ +#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR3 register ********************/ +#define ADC_SQR3_SQ10_Pos (0U) +#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ +#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ +#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ +#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ +#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ +#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ +#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ + +#define ADC_SQR3_SQ11_Pos (6U) +#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ +#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ +#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ +#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ +#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ +#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ +#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ + +#define ADC_SQR3_SQ12_Pos (12U) +#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ +#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ +#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ +#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ +#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ +#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ +#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ + +#define ADC_SQR3_SQ13_Pos (18U) +#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ +#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ +#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ +#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ +#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ +#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ +#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ + +#define ADC_SQR3_SQ14_Pos (24U) +#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ +#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ +#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ +#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ +#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ +#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ +#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR4 register ********************/ +#define ADC_SQR4_SQ15_Pos (0U) +#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ +#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ +#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ +#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ +#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ +#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ +#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ + +#define ADC_SQR4_SQ16_Pos (6U) +#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ +#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ +#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ +#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ +#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ +#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ +#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ +/******************** Bit definition for ADC_DR register ********************/ +#define ADC_DR_RDATA_Pos (0U) +#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ + +/******************** Bit definition for ADC_JSQR register ********************/ +#define ADC_JSQR_JL_Pos (0U) +#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ +#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ +#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ +#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ + +#define ADC_JSQR_JEXTSEL_Pos (2U) +#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ +#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ +#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ +#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ +#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ +#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ + +#define ADC_JSQR_JEXTEN_Pos (7U) +#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ +#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ +#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ +#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ + +#define ADC_JSQR_JSQ1_Pos (9U) +#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ +#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ +#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ +#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ +#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ +#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ +#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ + +#define ADC_JSQR_JSQ2_Pos (15U) +#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ +#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ +#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ +#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ +#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ +#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ +#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ + +#define ADC_JSQR_JSQ3_Pos (21U) +#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ +#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ +#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ +#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ +#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ +#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ +#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ + +#define ADC_JSQR_JSQ4_Pos (27U) +#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ +#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ +#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ +#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ +#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ +#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ +#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_OFR1 register ********************/ +#define ADC_OFR1_OFFSET1_Pos (0U) +#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ +#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ +#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ +#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ +#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ +#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ +#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ +#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ +#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ +#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ +#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ +#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ +#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ +#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ +#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ +#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ +#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ +#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ +#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ +#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ +#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ +#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ +#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ +#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ +#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ +#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ +#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ + +#define ADC_OFR1_OFFSET1_CH_Pos (26U) +#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ +#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR1_SSATE_Pos (31U) +#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR1_OFFSET1_Pos (0U) +#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR1_OFFSETPOS_Pos (24U) +#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ +#define ADC3_OFR1_SATEN_Pos (25U) +#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ + +#define ADC3_OFR1_OFFSET1_EN_Pos (31U) +#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ + +/******************** Bit definition for ADC_OFR2 register ********************/ +#define ADC_OFR2_OFFSET2_Pos (0U) +#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ +#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ +#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ +#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ +#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ +#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ +#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ +#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ +#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ +#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ +#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ +#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ +#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ +#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ +#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ +#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ +#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ +#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ +#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ +#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ +#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ +#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ +#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ +#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ +#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ +#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ +#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ + +#define ADC_OFR2_OFFSET2_CH_Pos (26U) +#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ +#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR2_SSATE_Pos (31U) +#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR2_OFFSET2_Pos (0U) +#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR2_OFFSETPOS_Pos (24U) +#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ +#define ADC3_OFR2_SATEN_Pos (25U) +#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ + +#define ADC3_OFR2_OFFSET2_EN_Pos (31U) +#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ + +/******************** Bit definition for ADC_OFR3 register ********************/ +#define ADC_OFR3_OFFSET3_Pos (0U) +#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ +#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ +#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ +#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ +#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ +#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ +#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ +#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ +#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ +#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ +#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ +#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ +#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ +#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ +#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ +#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ +#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ +#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ +#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ +#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ +#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ +#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ +#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ +#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ +#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ +#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ +#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ + +#define ADC_OFR3_OFFSET3_CH_Pos (26U) +#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ +#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR3_SSATE_Pos (31U) +#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR3_OFFSET3_Pos (0U) +#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR3_OFFSETPOS_Pos (24U) +#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ +#define ADC3_OFR3_SATEN_Pos (25U) +#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ + +#define ADC3_OFR3_OFFSET3_EN_Pos (31U) +#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ + +/******************** Bit definition for ADC_OFR4 register ********************/ +#define ADC_OFR4_OFFSET4_Pos (0U) +#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ +#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ +#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ +#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ +#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ +#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ +#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ +#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ +#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ +#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ +#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ +#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ +#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ +#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ +#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ +#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ +#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ +#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ +#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ +#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ +#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ +#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ +#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ +#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ +#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ +#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ +#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ + +#define ADC_OFR4_OFFSET4_CH_Pos (26U) +#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ +#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR4_SSATE_Pos (31U) +#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR4_OFFSET4_Pos (0U) +#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR4_OFFSETPOS_Pos (24U) +#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ +#define ADC3_OFR4_SATEN_Pos (25U) +#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ + +#define ADC3_OFR4_OFFSET4_EN_Pos (31U) +#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ + +/******************** Bit definition for ADC_JDR1 register ********************/ +#define ADC_JDR1_JDATA_Pos (0U) +#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR2 register ********************/ +#define ADC_JDR2_JDATA_Pos (0U) +#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR3 register ********************/ +#define ADC_JDR3_JDATA_Pos (0U) +#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR4 register ********************/ +#define ADC_JDR4_JDATA_Pos (0U) +#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_AWD2CR register ********************/ +#define ADC_AWD2CR_AWD2CH_Pos (0U) +#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ +#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ +#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ +#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_AWD3CR register ********************/ +#define ADC_AWD3CR_AWD3CH_Pos (0U) +#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ +#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ +#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ +#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_DIFSEL register ********************/ +#define ADC_DIFSEL_DIFSEL_Pos (0U) +#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ +#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ +#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ +#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ +#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ +#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ +#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ +#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ +#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ +#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ +#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ +#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ +#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ +#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ +#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ +#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ +#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ +#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ +#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ +#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ +#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ +#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_CALFACT register ********************/ +#define ADC_CALFACT_CALFACT_S_Pos (0U) +#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ +#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ +#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ +#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ +#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ +#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ +#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ +#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ +#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ +#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ +#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ +#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ +#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ +#define ADC_CALFACT_CALFACT_D_Pos (16U) +#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ +#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ +#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ +#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ +#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ +#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ +#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ +#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ +#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ +#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ +#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ +#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ +#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ + +/******************** Bit definition for ADC_CALFACT2 register ********************/ +#define ADC_CALFACT2_LINCALFACT_Pos (0U) +#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ +#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ +#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ +#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ +#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ +#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ +#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ +#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ +#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ +#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ +#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ +#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ +#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ +#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ +#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ +#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ +#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ +#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ +#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ +#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ +#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ +#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ +#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ +#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ +#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ +#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ +#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ +#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ +#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ +#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ +#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ +#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ + +/************************* ADC Common registers *****************************/ +/******************** Bit definition for ADC_CSR register ********************/ +#define ADC_CSR_ADRDY_MST_Pos (0U) +#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ +#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ +#define ADC_CSR_EOSMP_MST_Pos (1U) +#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ +#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ +#define ADC_CSR_EOC_MST_Pos (2U) +#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ +#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ +#define ADC_CSR_EOS_MST_Pos (3U) +#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ +#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ +#define ADC_CSR_OVR_MST_Pos (4U) +#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ +#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ +#define ADC_CSR_JEOC_MST_Pos (5U) +#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ +#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ +#define ADC_CSR_JEOS_MST_Pos (6U) +#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ +#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ +#define ADC_CSR_AWD1_MST_Pos (7U) +#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ +#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ +#define ADC_CSR_AWD2_MST_Pos (8U) +#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ +#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ +#define ADC_CSR_AWD3_MST_Pos (9U) +#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ +#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ +#define ADC_CSR_JQOVF_MST_Pos (10U) +#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ +#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ +#define ADC_CSR_ADRDY_SLV_Pos (16U) +#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ +#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ +#define ADC_CSR_EOSMP_SLV_Pos (17U) +#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ +#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ +#define ADC_CSR_EOC_SLV_Pos (18U) +#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ +#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ +#define ADC_CSR_EOS_SLV_Pos (19U) +#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ +#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ +#define ADC_CSR_OVR_SLV_Pos (20U) +#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ +#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ +#define ADC_CSR_JEOC_SLV_Pos (21U) +#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ +#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ +#define ADC_CSR_JEOS_SLV_Pos (22U) +#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ +#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ +#define ADC_CSR_AWD1_SLV_Pos (23U) +#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ +#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ +#define ADC_CSR_AWD2_SLV_Pos (24U) +#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ +#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ +#define ADC_CSR_AWD3_SLV_Pos (25U) +#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ +#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ +#define ADC_CSR_JQOVF_SLV_Pos (26U) +#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ +#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ + +/******************** Bit definition for ADC_CCR register ********************/ +#define ADC_CCR_DUAL_Pos (0U) +#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ +#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ +#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ +#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ +#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ +#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ +#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ + +#define ADC_CCR_DELAY_Pos (8U) +#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ +#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ +#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ +#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ +#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ +#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ + + +#define ADC_CCR_DAMDF_Pos (14U) +#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ +#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ +#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ +#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ + +#define ADC_CCR_CKMODE_Pos (16U) +#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ +#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ +#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ +#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ + +#define ADC_CCR_PRESC_Pos (18U) +#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ +#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ +#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ +#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ +#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ +#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ + +#define ADC_CCR_VREFEN_Pos (22U) +#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ +#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ +#define ADC_CCR_TSEN_Pos (23U) +#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ +#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ +#define ADC_CCR_VBATEN_Pos (24U) +#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ +#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ + +/******************** Bit definition for ADC_CDR register *******************/ +#define ADC_CDR_RDATA_MST_Pos (0U) +#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ +#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ + +#define ADC_CDR_RDATA_SLV_Pos (16U) +#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ +#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ + +/******************** Bit definition for ADC_CDR2 register ******************/ +#define ADC_CDR2_RDATA_ALT_Pos (0U) +#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ +#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ + + +/******************************************************************************/ +/* */ +/* VREFBUF */ +/* */ +/******************************************************************************/ +/******************* Bit definition for VREFBUF_CSR register ****************/ +#define VREFBUF_CSR_ENVR_Pos (0U) +#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ +#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ +#define DAC_CR_CEN1_Pos (14U) +#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ +#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ + +#define DAC_CR_EN2_Pos (16U) +#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ +#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ +#define DAC_CR_CEN2_Pos (30U) +#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ +#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ + +/***************** Bit definition for DAC_SWTRIGR register ******************/ +#define DAC_SWTRIGR_SWTRIG1_Pos (0U) +#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ +#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!
© 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 + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS_Device + * @{ + */ + +/** @addtogroup stm32h735xx + * @{ + */ + +#ifndef STM32H735xx_H +#define STM32H735xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32H7XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ + PVD_AVD_IRQn = 1, /*!< PVD/AVD 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 and ADC2 global Interrupts */ + FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ + FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ + FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ + FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation 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 */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FMC_IRQn = 48, /*!< FMC global Interrupt */ + SDMMC1_IRQn = 49, /*!< SDMMC1 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 */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ + CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ + HASH_RNG_IRQn = 80, /*!< HASH and 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 */ + SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ + SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ + LTDC_IRQn = 88, /*!< LTDC global Interrupt */ + LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ + DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ + OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ + LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ + CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ + I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ + I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ + SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ + DMAMUX1_OVR_IRQn = 102, /*! + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ + __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ + __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ + __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ + __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ + __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ + __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ + __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x02C */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ + __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ + uint32_t RESERVED3; /*!< Reserved, 0x044 */ + uint32_t RESERVED4; /*!< Reserved, 0x048 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ + uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ + __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ + __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ + __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ + __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ + uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ + uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ + __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ + __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ + uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ + uint32_t RESERVED9; /*!< Reserved, 0x0AC */ + __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ + __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ + __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ + __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ + __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ + __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ + __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ +} ADC_TypeDef; + + +typedef struct +{ +__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ +uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ +__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ +__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ +__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ + +} ADC_Common_TypeDef; + + +/** + * @brief VREFBUF + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ + __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ +} VREFBUF_TypeDef; + + +/** + * @brief FD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ + __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ + __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ + __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ + __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ + __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ + __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ + __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ + __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ + __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ + __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ + __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ + __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ + __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ + __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ + __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ + __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ + __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ + __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ + __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ + __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ + __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ + __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ + __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ + __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ + __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ + __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ + __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ + __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ + __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ + __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ + __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ + __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ + __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ + __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ + __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ + __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ + __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ + __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ + __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ + __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ + __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ + __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ + __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ + __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ + __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ + __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ + __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ + __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ + __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ + __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ + __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ + __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ +} FDCAN_GlobalTypeDef; + +/** + * @brief TTFD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ + __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ + __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ + __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ + __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ + __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ + __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ + __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ + __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ + __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ + __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ + __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ + __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ + __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ + __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ + __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ + __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ + __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ + __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ +} TTCAN_TypeDef; + +/** + * @brief FD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ + __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ + __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ + __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ + __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ + __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ +} FDCAN_ClockCalibrationUnit_TypeDef; + + +/** + * @brief Consumer Electronics Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ + __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ + __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ + __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ + __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ + __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ +}CEC_TypeDef; + +/** + * @brief COordincate Rotation DIgital Computer + */ +typedef struct +{ + __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ + __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ + __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ +} CORDIC_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED2; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +} CRC_TypeDef; + + +/** + * @brief Clock Recovery System + */ +typedef struct +{ +__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ +__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ +__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ +__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ +} CRS_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 */ + __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ + __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ + __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ + __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ + __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ + __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ +} DAC_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 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 */ + uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ + __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ + uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ + __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ + __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ + __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ + uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ + __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ + __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ + __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ + __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ + __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ + __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ + __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ + __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ + __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ + __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ + __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ + __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ +}DBGMCU_TypeDef; +/** + * @brief DCMI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ + __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ + __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ + __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ + __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ + __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ + __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ + __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ + __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ + __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ + __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ +} DCMI_TypeDef; + +/** + * @brief PSSI + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ + __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ + __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ + __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ + __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ + __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ + __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ + __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ + __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ + __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ + __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ + __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ + __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ +} PSSI_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; + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ + __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ +} BDMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +} BDMA_TypeDef; + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ +}DMAMUX_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< DMA Channel Status Register */ + __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ +}DMAMUX_ChannelStatus_TypeDef; + +typedef struct +{ + __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ +}DMAMUX_RequestGen_TypeDef; + +typedef struct +{ + __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ + __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ +}DMAMUX_RequestGenStatus_TypeDef; + +/** + * @brief MDMA Controller + */ +typedef struct +{ + __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ +}MDMA_TypeDef; + +typedef struct +{ + __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ + __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ + __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ + __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ + __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ + __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ + __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ + __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ + __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ + __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ + __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ + uint32_t RESERVED0; /*!< Reserved, 0x6C */ + __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ + __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ +}MDMA_Channel_TypeDef; + +/** + * @brief DMA2D Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ + __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ + __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ + __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ + __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ + __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ + __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ + __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ + __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ + __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ + __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ + __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ + __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ + __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ + __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ + __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ + __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ + __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ + __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ + __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ + uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ + __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ + __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ +} DMA2D_TypeDef; + + +/** + * @brief Ethernet MAC + */ +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACECR; + __IO uint32_t MACPFR; + __IO uint32_t MACWTR; + __IO uint32_t MACHT0R; + __IO uint32_t MACHT1R; + uint32_t RESERVED1[14]; + __IO uint32_t MACVTR; + uint32_t RESERVED2; + __IO uint32_t MACVHTR; + uint32_t RESERVED3; + __IO uint32_t MACVIR; + __IO uint32_t MACIVIR; + uint32_t RESERVED4[2]; + __IO uint32_t MACTFCR; + uint32_t RESERVED5[7]; + __IO uint32_t MACRFCR; + uint32_t RESERVED6[7]; + __IO uint32_t MACISR; + __IO uint32_t MACIER; + __IO uint32_t MACRXTXSR; + uint32_t RESERVED7; + __IO uint32_t MACPCSR; + __IO uint32_t MACRWKPFR; + uint32_t RESERVED8[2]; + __IO uint32_t MACLCSR; + __IO uint32_t MACLTCR; + __IO uint32_t MACLETR; + __IO uint32_t MAC1USTCR; + uint32_t RESERVED9[12]; + __IO uint32_t MACVR; + __IO uint32_t MACDR; + uint32_t RESERVED10; + __IO uint32_t MACHWF0R; + __IO uint32_t MACHWF1R; + __IO uint32_t MACHWF2R; + uint32_t RESERVED11[54]; + __IO uint32_t MACMDIOAR; + __IO uint32_t MACMDIODR; + uint32_t RESERVED12[2]; + __IO uint32_t MACARPAR; + uint32_t RESERVED13[59]; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; + uint32_t RESERVED14[248]; + __IO uint32_t MMCCR; + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; + uint32_t RESERVED15[14]; + __IO uint32_t MMCTSCGPR; + __IO uint32_t MMCTMCGPR; + uint32_t RESERVED16[5]; + __IO uint32_t MMCTPCGR; + uint32_t RESERVED17[10]; + __IO uint32_t MMCRCRCEPR; + __IO uint32_t MMCRAEPR; + uint32_t RESERVED18[10]; + __IO uint32_t MMCRUPGR; + uint32_t RESERVED19[9]; + __IO uint32_t MMCTLPIMSTR; + __IO uint32_t MMCTLPITCR; + __IO uint32_t MMCRLPIMSTR; + __IO uint32_t MMCRLPITCR; + uint32_t RESERVED20[65]; + __IO uint32_t MACL3L4C0R; + __IO uint32_t MACL4A0R; + uint32_t RESERVED21[2]; + __IO uint32_t MACL3A0R0R; + __IO uint32_t MACL3A1R0R; + __IO uint32_t MACL3A2R0R; + __IO uint32_t MACL3A3R0R; + uint32_t RESERVED22[4]; + __IO uint32_t MACL3L4C1R; + __IO uint32_t MACL4A1R; + uint32_t RESERVED23[2]; + __IO uint32_t MACL3A0R1R; + __IO uint32_t MACL3A1R1R; + __IO uint32_t MACL3A2R1R; + __IO uint32_t MACL3A3R1R; + uint32_t RESERVED24[108]; + __IO uint32_t MACTSCR; + __IO uint32_t MACSSIR; + __IO uint32_t MACSTSR; + __IO uint32_t MACSTNR; + __IO uint32_t MACSTSUR; + __IO uint32_t MACSTNUR; + __IO uint32_t MACTSAR; + uint32_t RESERVED25; + __IO uint32_t MACTSSR; + uint32_t RESERVED26[3]; + __IO uint32_t MACTTSSNR; + __IO uint32_t MACTTSSSR; + uint32_t RESERVED27[2]; + __IO uint32_t MACACR; + uint32_t RESERVED28; + __IO uint32_t MACATSNR; + __IO uint32_t MACATSSR; + __IO uint32_t MACTSIACR; + __IO uint32_t MACTSEACR; + __IO uint32_t MACTSICNR; + __IO uint32_t MACTSECNR; + uint32_t RESERVED29[4]; + __IO uint32_t MACPPSCR; + uint32_t RESERVED30[3]; + __IO uint32_t MACPPSTTSR; + __IO uint32_t MACPPSTTNR; + __IO uint32_t MACPPSIR; + __IO uint32_t MACPPSWR; + uint32_t RESERVED31[12]; + __IO uint32_t MACPOCR; + __IO uint32_t MACSPI0R; + __IO uint32_t MACSPI1R; + __IO uint32_t MACSPI2R; + __IO uint32_t MACLMIR; + uint32_t RESERVED32[11]; + __IO uint32_t MTLOMR; + uint32_t RESERVED33[7]; + __IO uint32_t MTLISR; + uint32_t RESERVED34[55]; + __IO uint32_t MTLTQOMR; + __IO uint32_t MTLTQUR; + __IO uint32_t MTLTQDR; + uint32_t RESERVED35[8]; + __IO uint32_t MTLQICSR; + __IO uint32_t MTLRQOMR; + __IO uint32_t MTLRQMPOCR; + __IO uint32_t MTLRQDR; + uint32_t RESERVED36[177]; + __IO uint32_t DMAMR; + __IO uint32_t DMASBMR; + __IO uint32_t DMAISR; + __IO uint32_t DMADSR; + uint32_t RESERVED37[60]; + __IO uint32_t DMACCR; + __IO uint32_t DMACTCR; + __IO uint32_t DMACRCR; + uint32_t RESERVED38[2]; + __IO uint32_t DMACTDLAR; + uint32_t RESERVED39; + __IO uint32_t DMACRDLAR; + __IO uint32_t DMACTDTPR; + uint32_t RESERVED40; + __IO uint32_t DMACRDTPR; + __IO uint32_t DMACTDRLR; + __IO uint32_t DMACRDRLR; + __IO uint32_t DMACIER; + __IO uint32_t DMACRIWTR; +__IO uint32_t DMACSFCSR; + uint32_t RESERVED41; + __IO uint32_t DMACCATDR; + uint32_t RESERVED42; + __IO uint32_t DMACCARDR; + uint32_t RESERVED43; + __IO uint32_t DMACCATBR; + uint32_t RESERVED44; + __IO uint32_t DMACCARBR; + __IO uint32_t DMACSR; +uint32_t RESERVED45[2]; +__IO uint32_t DMACMFCR; +}ETH_TypeDef; +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ +__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ +__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ +__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ +__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ +__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ +__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ +uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ +__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ +__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ +__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ +__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ +__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ +__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ +uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ +__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ +__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ +__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ +__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ +__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ +__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ +uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ +__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ +__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ +__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ +uint32_t RESERVED4; /*!< Reserved, 0x8C */ +__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ +__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ +__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ +uint32_t RESERVED5; /*!< Reserved, 0x9C */ +__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ +__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ +__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ +}EXTI_TypeDef; + +/** + * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 + * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. + * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: + * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) + * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) + * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only + */ + +typedef struct +{ +__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ +__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ +__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ +uint32_t RESERVED1; /*!< Reserved, 0x0C */ +__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ +__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ +__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ +uint32_t RESERVED2; /*!< Reserved, 0x1C */ +__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ +__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ +__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ +}EXTI_Core_TypeDef; + + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ + __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ + __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ + __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ + __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ + __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ + __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ + __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ + __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ + __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ + __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ + __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ + __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ + __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ + __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ + __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ + __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ + __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ + __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ + __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ + uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ + __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ + __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ +} FLASH_TypeDef; + +/** + * @brief Filter and Mathematical ACcelerator + */ +typedef struct +{ + __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ + __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ + __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ + __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ + __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ + __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ +} FMAC_TypeDef; + +/** + * @brief Flexible 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 */ +} FMC_Bank1_TypeDef; + +/** + * @brief Flexible Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FMC_Bank1E_TypeDef; + +/** + * @brief Flexible Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ +} FMC_Bank2_TypeDef; + +/** + * @brief Flexible Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FMC_Bank3_TypeDef; + +/** + * @brief Flexible Memory Controller Bank5 and 6 + */ + + +typedef struct +{ + __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ + __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ + __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ + __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ + __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ +} FMC_Bank5_6_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, 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 Operational Amplifier (OPAMP) + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ + __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ + __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ +} OPAMP_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ + __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ + __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ + __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ + __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ + __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ + uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ + __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ + uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ + __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ + __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ + __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ + __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ + __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ + __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ + __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ + __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ + uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ + __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ + __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ + __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ + __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ + __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ + __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ + __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ + __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ + +} 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 1 register, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ + __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ + __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ + __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ + __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ + __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ + __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ + __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ + __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ +} IWDG_TypeDef; + + +/** + * @brief LCD-TFT Display Controller + */ + +typedef struct +{ + uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ + __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ + __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ + __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ + __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ + __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ + __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ + uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ + __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ + uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ + __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ + __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ + __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ + __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ + __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ + __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ +} LTDC_TypeDef; + +/** + * @brief LCD-TFT Display layer x Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ + __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ + __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ + __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ + __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ + __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ + __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ + __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ + uint32_t RESERVED0[2]; /*!< Reserved */ + __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ + __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ + __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ + uint32_t RESERVED1[3]; /*!< Reserved */ + __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ + +} LTDC_Layer_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ + __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ + __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ + __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ + uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ + __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ + __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ + __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ + __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ + __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ + __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ + __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ + __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ + __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ + __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ + __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ + __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ + __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ + __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ + __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ + __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ + __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ + __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ + __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ + __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ + __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ + __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ + __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ + __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ + uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ + __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ + __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ + __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ + __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ + __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ + __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ + __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ + uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ + __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ + uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ + __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ + __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ + __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ + __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ + __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ + __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ + uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ + __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ + __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ + __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ + __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ + __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ + uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ + +} 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 */ + uint32_t RESERVED; /*!< Reserved, 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 TAMPCR; /*!< RTC tamper 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 */ + __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 0, 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 */ + __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ + __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ + __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ + __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ + __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ + __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ + __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ + __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ + __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ + __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ + __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ + __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ +} RTC_TypeDef; + +/** + * @brief Serial Audio Interface + */ + +typedef struct +{ + __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ + uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ + __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ + __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ +} 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 SPDIF-RX Interface + */ + +typedef struct +{ + __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ + __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ + __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ + __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ + __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ + __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1A */ +} SPDIFRX_TypeDef; + + +/** + * @brief Secure digital input/output Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ + __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ + __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ + __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ + __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ + __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ + __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ + __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ + __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ + uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ + __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ + __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ + __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ + __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ + uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ + __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ + uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ + __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ +} SDMMC_TypeDef; + + +/** + * @brief Delay Block DLYB + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ + __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ +} DLYB_TypeDef; + +/** + * @brief HW Semaphore HSEM + */ + +typedef struct +{ + __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ + __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ + __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ + __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ + __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ + __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ + uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ + __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ + __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ + +} HSEM_TypeDef; + +typedef struct +{ + __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ + __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ + __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ + __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ +} HSEM_Common_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ + __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ + __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ + __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ + __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ + uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ + __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ + uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ + __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ + __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ + __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ + __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ + __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ + +} SPI_TypeDef; + +/** + * @brief DTS + */ +typedef struct +{ + __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ + uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ + __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ + __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ + __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ + __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ + __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ + __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ + __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ + __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ +} +DTS_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 */ + uint32_t RESERVED1; /*!< Reserved, 0x50 */ + __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ + __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ + __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ + __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ + __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ + __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ +} TIM_TypeDef; + +/** + * @brief LPTIMIMER + */ +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 */ + uint32_t RESERVED1; /*!< Reserved, 0x20 */ + __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ +} LPTIM_TypeDef; + +/** + * @brief Comparator + */ +typedef struct +{ + __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ + __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ + __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ +} COMPOPT_TypeDef; + +typedef struct +{ + __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ +} COMP_TypeDef; + +typedef struct +{ + __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ +} COMP_Common_TypeDef; +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ + __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ + __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ + __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ + __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ + __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ + __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ + __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ +} USART_TypeDef; + +/** + * @brief Single Wire Protocol Master Interface SPWMI + */ +typedef struct +{ + __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ + __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ + uint32_t RESERVED1; /*!< Reserved, 0x08 */ + __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ + __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ + __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ + __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ + __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ + __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ +} SWPMI_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 RAM_ECC_Specific_Registers + */ +typedef struct +{ + __IO uint32_t CR; /*!< RAMECC monitor configuration register */ + __IO uint32_t SR; /*!< RAMECC monitor status register */ + __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ + __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ + __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ + __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ +} RAMECC_MonitorTypeDef; + +typedef struct +{ + __IO uint32_t IER; /*!< RAMECC interrupt enable register */ +} RAMECC_TypeDef; +/** + * @} + */ + + +/** + * @brief Crypto Processor + */ + +typedef struct +{ + __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ + __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ + __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ + __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ + __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ + __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ + __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ + __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ + __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ + __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ + __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ + __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ + __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ + __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ + __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ + __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ + __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ + __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ + __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ + __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ + __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ + __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ + __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ + __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ + __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ + __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ + __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ + __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ + __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ + __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ + __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ + __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ + __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ + __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ + __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ +} CRYP_TypeDef; + +/** + * @brief HASH + */ + +typedef struct +{ + __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ + __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ + __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ + __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ + __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ + __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ + uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ + __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ +} HASH_TypeDef; + +/** + * @brief HASH_DIGEST + */ + +typedef struct +{ + __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ +} HASH_DIGEST_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 */ + uint32_t RESERVED; + __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ +} RNG_TypeDef; + +/** + * @brief MDIOS + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t WRFR; + __IO uint32_t CWRFR; + __IO uint32_t RDFR; + __IO uint32_t CRDFR; + __IO uint32_t SR; + __IO uint32_t CLRFR; + uint32_t RESERVED[57]; + __IO uint32_t DINR0; + __IO uint32_t DINR1; + __IO uint32_t DINR2; + __IO uint32_t DINR3; + __IO uint32_t DINR4; + __IO uint32_t DINR5; + __IO uint32_t DINR6; + __IO uint32_t DINR7; + __IO uint32_t DINR8; + __IO uint32_t DINR9; + __IO uint32_t DINR10; + __IO uint32_t DINR11; + __IO uint32_t DINR12; + __IO uint32_t DINR13; + __IO uint32_t DINR14; + __IO uint32_t DINR15; + __IO uint32_t DINR16; + __IO uint32_t DINR17; + __IO uint32_t DINR18; + __IO uint32_t DINR19; + __IO uint32_t DINR20; + __IO uint32_t DINR21; + __IO uint32_t DINR22; + __IO uint32_t DINR23; + __IO uint32_t DINR24; + __IO uint32_t DINR25; + __IO uint32_t DINR26; + __IO uint32_t DINR27; + __IO uint32_t DINR28; + __IO uint32_t DINR29; + __IO uint32_t DINR30; + __IO uint32_t DINR31; + __IO uint32_t DOUTR0; + __IO uint32_t DOUTR1; + __IO uint32_t DOUTR2; + __IO uint32_t DOUTR3; + __IO uint32_t DOUTR4; + __IO uint32_t DOUTR5; + __IO uint32_t DOUTR6; + __IO uint32_t DOUTR7; + __IO uint32_t DOUTR8; + __IO uint32_t DOUTR9; + __IO uint32_t DOUTR10; + __IO uint32_t DOUTR11; + __IO uint32_t DOUTR12; + __IO uint32_t DOUTR13; + __IO uint32_t DOUTR14; + __IO uint32_t DOUTR15; + __IO uint32_t DOUTR16; + __IO uint32_t DOUTR17; + __IO uint32_t DOUTR18; + __IO uint32_t DOUTR19; + __IO uint32_t DOUTR20; + __IO uint32_t DOUTR21; + __IO uint32_t DOUTR22; + __IO uint32_t DOUTR23; + __IO uint32_t DOUTR24; + __IO uint32_t DOUTR25; + __IO uint32_t DOUTR26; + __IO uint32_t DOUTR27; + __IO uint32_t DOUTR28; + __IO uint32_t DOUTR29; + __IO uint32_t DOUTR30; + __IO uint32_t DOUTR31; +} MDIOS_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 */ + __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ + __IO uint32_t GHWCFG1; /* User HW config1 044h*/ + __IO uint32_t GHWCFG2; /* User HW config2 048h*/ + __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ + uint32_t Reserved6; /*!< Reserved 050h */ + __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ + __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ + __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ + __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ + uint32_t Reserved43[39]; /*!< 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 OCTO Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ + uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ + __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ + __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ + __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ + __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ + uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ + __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ + __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ + uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ + __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ + __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ + uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ + __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ + uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ + __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ + __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ + __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ + uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ + __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ + uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ + __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ + uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ + __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ + uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ + __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ + uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ + __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ + uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ + __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ + uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ + __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ + uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ + __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ + uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ + __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ + uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ + __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ + uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ + __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ + uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ + __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ + uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ + __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ + uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ + __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ + uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ + __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ + __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ + __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ + __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ +} OCTOSPI_TypeDef; + +/** + * @} + */ +/** + * @brief OCTO Serial Peripheral Interface IO Manager + */ + +typedef struct +{ + __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ + __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ +} OCTOSPIM_TypeDef; + +/** + * @} + */ + +/** + * @brief OTFD register + */ +typedef struct +{ + __IO uint32_t REG_CONFIGR; + __IO uint32_t REG_START_ADDR; + __IO uint32_t REG_END_ADDR; + __IO uint32_t REG_NONCER0; + __IO uint32_t REG_NONCER1; + __IO uint32_t REG_KEYR0; + __IO uint32_t REG_KEYR1; + __IO uint32_t REG_KEYR2; + __IO uint32_t REG_KEYR3; +} OTFDEC_Region_TypeDef; + +typedef struct +{ + __IO uint32_t CR; + uint32_t RESERVED1[191]; + __IO uint32_t ISR; + __IO uint32_t ICR; + __IO uint32_t IER; + uint32_t RESERVED2[56]; + __IO uint32_t HWCFGR2; + __IO uint32_t HWCFGR1; + __IO uint32_t VERR; + __IO uint32_t IPIDR; + __IO uint32_t SIDR; +} OTFDEC_TypeDef; +/** + * @} + */ + +/** + * @brief Global Programmer View + */ + +typedef struct +{ + uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ + __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ + uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ + uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ + uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ + __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ + __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ + __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ + __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ + __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ + __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ + __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ + __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ + uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ + __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ + uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ + __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ + __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ + uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ + __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ + uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ + __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ + uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ + __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ + __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ + uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ + __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ + uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ + __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ + uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ + __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ + uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ + __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ + uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ + __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ + uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ + __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ + uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ + __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ + uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ + __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ + uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ + __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ + uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ + __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ + uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ + __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ + uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ + __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ + uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ + __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ + __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ + uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ + __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ + __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ + __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ + uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ + __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ + __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ + __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ + uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ + __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ + __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ + uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ + __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ + __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ + __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ + uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ + __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ + __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ + __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ + uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ + __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ + __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ + __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ + uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ + __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ + __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ + __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ + +} GPV_TypeDef; + +/** @addtogroup Peripheral_memory_map + * @{ + */ +#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ +#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ +#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ +#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ +#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ +#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ +#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ +#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ + +#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ +#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ +#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ + +#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ +#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ + +#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ +#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ +#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ + +#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ +#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ + + +/* Legacy define */ +#define FLASH_BASE FLASH_BANK1_BASE + +/*!< Device electronic signature memory map */ +#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ +#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ + + +/*!< Peripheral memory map */ +#define D2_APB1PERIPH_BASE PERIPH_BASE +#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) +#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) +#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) + +#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) +#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) + +#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) +#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) + +/*!< Legacy 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 + 0x08000000UL) + + +/*!< D1_AHB1PERIPH peripherals */ + +#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) +#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) +#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) +#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) +#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) +#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) +#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) +#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) +#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) +#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) +#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) +#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) + +#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) +#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) +#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) +#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) +#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) +#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) +#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) +#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) +#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) +#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) + +/*!< D2_AHB1PERIPH peripherals */ + +#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) +#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) +#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) +#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) +#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) +#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) +#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) +#define ETH_MAC_BASE (ETH_BASE) + +/*!< USB registers base address */ +#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) +#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) + +/*!< D2_AHB2PERIPH peripherals */ + +#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) +#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) +#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) +#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) +#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) +#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) +#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) +#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) +#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) +#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) +#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) + +/*!< D3_AHB1PERIPH peripherals */ +#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) +#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) +#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) +#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) +#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) +#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) +#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) +#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) +#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) +#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) +#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) +#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) +#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) +#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) +#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) +#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) +#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) +#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) +#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) + +/*!< D1_APB1PERIPH peripherals */ +#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) +#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) +#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) +#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) + +/*!< D2_APB1PERIPH peripherals */ +#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) +#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) +#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) +#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) +#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) +#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) +#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) +#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) +#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) +#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) + + +#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) +#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) +#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) +#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) +#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) +#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) +#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) +#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) +#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) +#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) +#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) +#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) +#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) +#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) +#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) +#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) +#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) +#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) +#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) +#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) +#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) +#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) +#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) +#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) +#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) +#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) +#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) +#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) + +/*!< D2_APB2PERIPH peripherals */ + +#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) +#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) +#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) +#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) +#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) +#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) +#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) +#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) +#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) +#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) +#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) +#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) +#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) +#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) +#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) +#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) +#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_Channel4_BASE (DFSDM1_BASE + 0x80UL) +#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) +#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) +#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) +#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) +#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) +#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) +#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) + + +/*!< D3_APB1PERIPH peripherals */ +#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) +#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) +#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) +#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) +#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) +#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) +#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) +#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) +#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) +#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) +#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) +#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) +#define COMP1_BASE (COMP12_BASE + 0x0CUL) +#define COMP2_BASE (COMP12_BASE + 0x10UL) +#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) +#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) +#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) + + +#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) +#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) +#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) + +#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) + + + +#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) +#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) +#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) +#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) +#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) +#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) +#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) +#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) + +#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) +#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) +#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) +#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) +#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) +#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) +#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) +#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) + +#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) +#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) +#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) +#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) +#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) +#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) +#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) +#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) + +#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) +#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) + +#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_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) + +#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) +#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) +#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) +#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) +#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) +#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) +#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) +#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) +#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) +#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) +#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) +#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) +#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) +#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) +#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) +#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) + +#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) +#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) +#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) +#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) +#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) +#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) +#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) +#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) + +#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) +#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) + +/*!< FMC Banks registers base address */ +#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) +#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) +#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) +#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) +#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE (0x5C001000UL) + +#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) +#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) +#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) +#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) +#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) +#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) +#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) +#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) +#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) +#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) +#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) +#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) +#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) +#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) +#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) +#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) + +#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) +#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) +#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) +#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) +#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) +#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) + +#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) +#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) +#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) + +#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) +#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) + + + +#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ + +/** + * @} + */ + +/** @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 TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) + + +#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define SPI4 ((SPI_TypeDef *) SPI4_BASE) +#define SPI5 ((SPI_TypeDef *) SPI5_BASE) +#define SPI6 ((SPI_TypeDef *) SPI6_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define USART10 ((USART_TypeDef *) USART10_BASE) +#define UART7 ((USART_TypeDef *) UART7_BASE) +#define UART8 ((USART_TypeDef *) UART8_BASE) +#define UART9 ((USART_TypeDef *) UART9_BASE) +#define CRS ((CRS_TypeDef *) CRS_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 I2C4 ((I2C_TypeDef *) I2C4_BASE) +#define I2C5 ((I2C_TypeDef *) I2C5_BASE) +#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) +#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) +#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) +#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) +#define TIM23 ((TIM_TypeDef *) TIM23_BASE) +#define TIM24 ((TIM_TypeDef *) TIM24_BASE) +#define CEC ((CEC_TypeDef *) CEC_BASE) +#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC1 ((DAC_TypeDef *) DAC1_BASE) +#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) +#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) +#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) +#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) +#define DTS ((DTS_TypeDef *) DTS_BASE) +#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) +#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) + +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) +#define COMP1 ((COMP_TypeDef *) COMP1_BASE) +#define COMP2 ((COMP_TypeDef *) COMP2_BASE) +#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) +#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) +#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) +#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) + + +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) +#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_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 SAI4 ((SAI_TypeDef *) SAI4_BASE) +#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) +#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) + +#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_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_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) +#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) +#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) +#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) +#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) +#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) +#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) +#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) +#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) +#define DCMI ((DCMI_TypeDef *) DCMI_BASE) +#define PSSI ((PSSI_TypeDef *) PSSI_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define CRC ((CRC_TypeDef *) CRC_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 GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) +#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) + +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) +#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) + +#define CRYP ((CRYP_TypeDef *) CRYP_BASE) +#define HASH ((HASH_TypeDef *) HASH_BASE) +#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) +#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) +#define FMAC ((FMAC_TypeDef *) FMAC_BASE) +#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) + +#define BDMA ((BDMA_TypeDef *) BDMA_BASE) +#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) +#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) +#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) +#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) +#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) +#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) +#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) +#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) + +#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) +#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) +#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) +#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) +#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) +#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) +#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) + +#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) +#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) +#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) +#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) + +#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) +#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) +#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) + +#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) +#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) +#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) +#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) +#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) +#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) +#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) +#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) +#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) + + +#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) +#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) +#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) +#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) +#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) +#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) +#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) +#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) + +#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) +#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_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 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 DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) +#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) +#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) +#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) +#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) +#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) +#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) +#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) +#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) +#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) +#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) +#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) +#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) +#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) +#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) +#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) +#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) + +#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) +#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) +#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) +#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) +#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) +#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) +#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) +#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) + +#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) +#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) + + +#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) +#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) +#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) +#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) +#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) + +#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) +#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) +#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) +#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) +#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) + +#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) +#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) +#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) +#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) +#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) + +#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) +#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) +#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) +#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) +#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) + +#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) +#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +#define HSEM ((HSEM_TypeDef *) HSEM_BASE) +#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) + +#define LTDC ((LTDC_TypeDef *)LTDC_BASE) +#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) +#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) + +#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) + +#define ETH ((ETH_TypeDef *)ETH_BASE) +#define MDMA ((MDMA_TypeDef *)MDMA_BASE) +#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) +#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) +#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) +#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) +#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) +#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) +#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) +#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) +#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) +#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) +#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) +#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) +#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) +#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) +#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) +#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) + + +#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) + +/* Legacy defines */ +#define USB_OTG_HS USB1_OTG_HS +#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE + +#define GPV ((GPV_TypeDef *) GPV_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************************* ADC VERSION ********************************/ +#define ADC_VER_V5_V90 +/******************** Bit definition for ADC_ISR register ********************/ +#define ADC_ISR_ADRDY_Pos (0U) +#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ +#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ +#define ADC_ISR_EOSMP_Pos (1U) +#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ +#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ +#define ADC_ISR_EOC_Pos (2U) +#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ +#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ +#define ADC_ISR_EOS_Pos (3U) +#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ +#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ +#define ADC_ISR_OVR_Pos (4U) +#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ +#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ +#define ADC_ISR_JEOC_Pos (5U) +#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ +#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ +#define ADC_ISR_JEOS_Pos (6U) +#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ +#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ +#define ADC_ISR_AWD1_Pos (7U) +#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ +#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ +#define ADC_ISR_AWD2_Pos (8U) +#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ +#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ +#define ADC_ISR_AWD3_Pos (9U) +#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ +#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ +#define ADC_ISR_JQOVF_Pos (10U) +#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ +#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ +#define ADC_ISR_LDORDY_Pos (12U) +#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ +#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ + +/******************** Bit definition for ADC_IER register ********************/ +#define ADC_IER_ADRDYIE_Pos (0U) +#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ +#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ +#define ADC_IER_EOSMPIE_Pos (1U) +#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ +#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ +#define ADC_IER_EOCIE_Pos (2U) +#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ +#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ +#define ADC_IER_EOSIE_Pos (3U) +#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ +#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ +#define ADC_IER_OVRIE_Pos (4U) +#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ +#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ +#define ADC_IER_JEOCIE_Pos (5U) +#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ +#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ +#define ADC_IER_JEOSIE_Pos (6U) +#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ +#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ +#define ADC_IER_AWD1IE_Pos (7U) +#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ +#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ +#define ADC_IER_AWD2IE_Pos (8U) +#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ +#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ +#define ADC_IER_AWD3IE_Pos (9U) +#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ +#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ +#define ADC_IER_JQOVFIE_Pos (10U) +#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ +#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ + +/******************** Bit definition for ADC_CR register ********************/ +#define ADC_CR_ADEN_Pos (0U) +#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ +#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ +#define ADC_CR_ADDIS_Pos (1U) +#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ +#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ +#define ADC_CR_ADSTART_Pos (2U) +#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ +#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ +#define ADC_CR_JADSTART_Pos (3U) +#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ +#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ +#define ADC_CR_ADSTP_Pos (4U) +#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ +#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ +#define ADC_CR_JADSTP_Pos (5U) +#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ +#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ +#define ADC_CR_BOOST_Pos (8U) +#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ +#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ +#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ +#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ +#define ADC_CR_ADCALLIN_Pos (16U) +#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ +#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ +#define ADC_CR_LINCALRDYW1_Pos (22U) +#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ +#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ +#define ADC_CR_LINCALRDYW2_Pos (23U) +#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ +#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ +#define ADC_CR_LINCALRDYW3_Pos (24U) +#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ +#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ +#define ADC_CR_LINCALRDYW4_Pos (25U) +#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ +#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ +#define ADC_CR_LINCALRDYW5_Pos (26U) +#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ +#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ +#define ADC_CR_LINCALRDYW6_Pos (27U) +#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ +#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ +#define ADC_CR_ADVREGEN_Pos (28U) +#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ +#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ +#define ADC_CR_DEEPPWD_Pos (29U) +#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ +#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ +#define ADC_CR_ADCALDIF_Pos (30U) +#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ +#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ +#define ADC_CR_ADCAL_Pos (31U) +#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ +#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ + +/******************** Bit definition for ADC_CFGR register ********************/ +#define ADC_CFGR_DMNGT_Pos (0U) +#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ +#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ +#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ +#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ + +#define ADC_CFGR_RES_Pos (2U) +#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ +#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ +#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ +#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ +#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ + +#define ADC_CFGR_EXTSEL_Pos (5U) +#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ +#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ +#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ +#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ +#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ +#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ + +#define ADC_CFGR_EXTEN_Pos (10U) +#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ +#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ +#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ +#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ + +#define ADC_CFGR_OVRMOD_Pos (12U) +#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ +#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ +#define ADC_CFGR_CONT_Pos (13U) +#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ +#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ +#define ADC_CFGR_AUTDLY_Pos (14U) +#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ +#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ + +#define ADC_CFGR_DISCEN_Pos (16U) +#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ +#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ + +#define ADC_CFGR_DISCNUM_Pos (17U) +#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ +#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ +#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ +#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ +#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ + +#define ADC_CFGR_JDISCEN_Pos (20U) +#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ +#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ +#define ADC_CFGR_JQM_Pos (21U) +#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ +#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ +#define ADC_CFGR_AWD1SGL_Pos (22U) +#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ +#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ +#define ADC_CFGR_AWD1EN_Pos (23U) +#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ +#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ +#define ADC_CFGR_JAWD1EN_Pos (24U) +#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ +#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ +#define ADC_CFGR_JAUTO_Pos (25U) +#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ +#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ + +#define ADC_CFGR_AWD1CH_Pos (26U) +#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ +#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ +#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ +#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ +#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ +#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ +#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ + +#define ADC_CFGR_JQDIS_Pos (31U) +#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ +#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ + +#define ADC3_CFGR_DMAEN_Pos (0U) +#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ +#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ +#define ADC3_CFGR_DMACFG_Pos (1U) +#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ +#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ + +#define ADC3_CFGR_RES_Pos (3U) +#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ +#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ +#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ +#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ + +#define ADC3_CFGR_ALIGN_Pos (15U) +#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ +#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ +/******************** Bit definition for ADC_CFGR2 register ********************/ +#define ADC_CFGR2_ROVSE_Pos (0U) +#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ +#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ +#define ADC_CFGR2_JOVSE_Pos (1U) +#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ +#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ + +#define ADC_CFGR2_OVSS_Pos (5U) +#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ +#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ +#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ +#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ +#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ +#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ + +#define ADC_CFGR2_TROVS_Pos (9U) +#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ +#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ +#define ADC_CFGR2_ROVSM_Pos (10U) +#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ +#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ + +#define ADC_CFGR2_RSHIFT1_Pos (11U) +#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ +#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ +#define ADC_CFGR2_RSHIFT2_Pos (12U) +#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ +#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ +#define ADC_CFGR2_RSHIFT3_Pos (13U) +#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ +#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ +#define ADC_CFGR2_RSHIFT4_Pos (14U) +#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ +#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ + +#define ADC_CFGR2_OVSR_Pos (16U) +#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ +#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ +#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ +#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ +#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ +#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ +#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ +#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ +#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ +#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ +#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ +#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ + +#define ADC_CFGR2_LSHIFT_Pos (28U) +#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ +#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ +#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ +#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ +#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ +#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ + +#define ADC3_CFGR2_OVSR_Pos (2U) +#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ +#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ +#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ +#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ +#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ + +#define ADC3_CFGR2_SWTRIG_Pos (25U) +#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ +#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ +#define ADC3_CFGR2_BULB_Pos (26U) +#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ +#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ +#define ADC3_CFGR2_SMPTRIG_Pos (27U) +#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ +#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ +/******************** Bit definition for ADC_SMPR1 register ********************/ +#define ADC_SMPR1_SMP0_Pos (0U) +#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ +#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ +#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ +#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ +#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR1_SMP1_Pos (3U) +#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ +#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ +#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ +#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ +#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR1_SMP2_Pos (6U) +#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ +#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ +#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ +#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR1_SMP3_Pos (9U) +#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ +#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ +#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ +#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR1_SMP4_Pos (12U) +#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ +#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ +#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ +#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ +#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR1_SMP5_Pos (15U) +#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ +#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ +#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ +#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ +#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR1_SMP6_Pos (18U) +#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ +#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ +#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ +#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR1_SMP7_Pos (21U) +#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ +#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ +#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ +#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR1_SMP8_Pos (24U) +#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ +#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ +#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ +#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ +#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ + +#define ADC_SMPR1_SMP9_Pos (27U) +#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ +#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ +#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ +#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ +#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ + +/******************** Bit definition for ADC_SMPR2 register ********************/ +#define ADC_SMPR2_SMP10_Pos (0U) +#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ +#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ +#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ +#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ +#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR2_SMP11_Pos (3U) +#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ +#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ +#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ +#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ +#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR2_SMP12_Pos (6U) +#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ +#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ +#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ +#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR2_SMP13_Pos (9U) +#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ +#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ +#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ +#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR2_SMP14_Pos (12U) +#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ +#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ +#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ +#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ +#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR2_SMP15_Pos (15U) +#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ +#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ +#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ +#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ +#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR2_SMP16_Pos (18U) +#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ +#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ +#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ +#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR2_SMP17_Pos (21U) +#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ +#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ +#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ +#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR2_SMP18_Pos (24U) +#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ +#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ +#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ +#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ +#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ + +#define ADC_SMPR2_SMP19_Pos (27U) +#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ +#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ +#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ +#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ +#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ + +/******************** Bit definition for ADC_PCSEL register ********************/ +#define ADC_PCSEL_PCSEL_Pos (0U) +#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ +#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ +#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ +#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ +#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ +#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ +#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ +#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ +#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ +#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ +#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ +#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ +#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ +#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ +#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ +#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ +#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ +#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ +#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ +#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ +#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ +#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ + +/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ +#define ADC_LTR_LT_Pos (0U) +#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ +#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ + +/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ +#define ADC_HTR_HT_Pos (0U) +#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ +#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ + +/******************** Bit definition for ADC3_TR1 register *******************/ +#define ADC3_TR1_LT1_Pos (0U) +#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ +#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ + +#define ADC3_TR1_AWDFILT_Pos (12U) +#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ +#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ +#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ +#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ +#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ + +#define ADC3_TR1_HT1_Pos (16U) +#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ +#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ + +/******************** Bit definition for ADC3_TR2 register *******************/ +#define ADC3_TR2_LT2_Pos (0U) +#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ +#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ + +#define ADC3_TR2_HT2_Pos (16U) +#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ +#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ + +/******************** Bit definition for ADC3_TR3 register *******************/ +#define ADC3_TR3_LT3_Pos (0U) +#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ +#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ + +#define ADC3_TR3_HT3_Pos (16U) +#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ +#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ + +/******************** Bit definition for ADC_SQR1 register ********************/ +#define ADC_SQR1_L_Pos (0U) +#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ +#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ +#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ +#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ +#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ +#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ + +#define ADC_SQR1_SQ1_Pos (6U) +#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ +#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ +#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ +#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ +#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ +#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ +#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ + +#define ADC_SQR1_SQ2_Pos (12U) +#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ +#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ +#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ +#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ +#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ +#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ +#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ + +#define ADC_SQR1_SQ3_Pos (18U) +#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ +#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ +#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ +#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ +#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ +#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ +#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ + +#define ADC_SQR1_SQ4_Pos (24U) +#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ +#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ +#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ +#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ +#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ +#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ +#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR2 register ********************/ +#define ADC_SQR2_SQ5_Pos (0U) +#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ +#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ +#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ +#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ +#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ +#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ +#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ + +#define ADC_SQR2_SQ6_Pos (6U) +#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ +#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ +#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ +#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ +#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ +#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ +#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ + +#define ADC_SQR2_SQ7_Pos (12U) +#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ +#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ +#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ +#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ +#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ +#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ +#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ + +#define ADC_SQR2_SQ8_Pos (18U) +#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ +#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ +#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ +#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ +#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ +#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ +#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ + +#define ADC_SQR2_SQ9_Pos (24U) +#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ +#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ +#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ +#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ +#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ +#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ +#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR3 register ********************/ +#define ADC_SQR3_SQ10_Pos (0U) +#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ +#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ +#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ +#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ +#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ +#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ +#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ + +#define ADC_SQR3_SQ11_Pos (6U) +#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ +#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ +#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ +#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ +#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ +#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ +#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ + +#define ADC_SQR3_SQ12_Pos (12U) +#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ +#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ +#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ +#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ +#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ +#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ +#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ + +#define ADC_SQR3_SQ13_Pos (18U) +#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ +#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ +#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ +#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ +#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ +#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ +#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ + +#define ADC_SQR3_SQ14_Pos (24U) +#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ +#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ +#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ +#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ +#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ +#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ +#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR4 register ********************/ +#define ADC_SQR4_SQ15_Pos (0U) +#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ +#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ +#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ +#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ +#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ +#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ +#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ + +#define ADC_SQR4_SQ16_Pos (6U) +#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ +#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ +#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ +#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ +#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ +#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ +#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ +/******************** Bit definition for ADC_DR register ********************/ +#define ADC_DR_RDATA_Pos (0U) +#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ + +/******************** Bit definition for ADC_JSQR register ********************/ +#define ADC_JSQR_JL_Pos (0U) +#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ +#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ +#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ +#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ + +#define ADC_JSQR_JEXTSEL_Pos (2U) +#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ +#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ +#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ +#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ +#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ +#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ + +#define ADC_JSQR_JEXTEN_Pos (7U) +#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ +#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ +#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ +#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ + +#define ADC_JSQR_JSQ1_Pos (9U) +#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ +#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ +#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ +#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ +#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ +#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ +#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ + +#define ADC_JSQR_JSQ2_Pos (15U) +#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ +#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ +#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ +#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ +#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ +#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ +#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ + +#define ADC_JSQR_JSQ3_Pos (21U) +#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ +#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ +#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ +#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ +#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ +#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ +#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ + +#define ADC_JSQR_JSQ4_Pos (27U) +#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ +#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ +#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ +#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ +#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ +#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ +#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_OFR1 register ********************/ +#define ADC_OFR1_OFFSET1_Pos (0U) +#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ +#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ +#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ +#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ +#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ +#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ +#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ +#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ +#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ +#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ +#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ +#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ +#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ +#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ +#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ +#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ +#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ +#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ +#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ +#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ +#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ +#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ +#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ +#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ +#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ +#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ +#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ + +#define ADC_OFR1_OFFSET1_CH_Pos (26U) +#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ +#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR1_SSATE_Pos (31U) +#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR1_OFFSET1_Pos (0U) +#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR1_OFFSETPOS_Pos (24U) +#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ +#define ADC3_OFR1_SATEN_Pos (25U) +#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ + +#define ADC3_OFR1_OFFSET1_EN_Pos (31U) +#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ + +/******************** Bit definition for ADC_OFR2 register ********************/ +#define ADC_OFR2_OFFSET2_Pos (0U) +#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ +#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ +#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ +#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ +#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ +#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ +#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ +#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ +#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ +#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ +#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ +#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ +#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ +#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ +#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ +#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ +#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ +#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ +#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ +#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ +#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ +#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ +#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ +#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ +#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ +#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ +#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ + +#define ADC_OFR2_OFFSET2_CH_Pos (26U) +#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ +#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR2_SSATE_Pos (31U) +#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR2_OFFSET2_Pos (0U) +#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR2_OFFSETPOS_Pos (24U) +#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ +#define ADC3_OFR2_SATEN_Pos (25U) +#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ + +#define ADC3_OFR2_OFFSET2_EN_Pos (31U) +#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ + +/******************** Bit definition for ADC_OFR3 register ********************/ +#define ADC_OFR3_OFFSET3_Pos (0U) +#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ +#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ +#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ +#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ +#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ +#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ +#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ +#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ +#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ +#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ +#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ +#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ +#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ +#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ +#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ +#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ +#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ +#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ +#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ +#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ +#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ +#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ +#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ +#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ +#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ +#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ +#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ + +#define ADC_OFR3_OFFSET3_CH_Pos (26U) +#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ +#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR3_SSATE_Pos (31U) +#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR3_OFFSET3_Pos (0U) +#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR3_OFFSETPOS_Pos (24U) +#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ +#define ADC3_OFR3_SATEN_Pos (25U) +#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ + +#define ADC3_OFR3_OFFSET3_EN_Pos (31U) +#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ + +/******************** Bit definition for ADC_OFR4 register ********************/ +#define ADC_OFR4_OFFSET4_Pos (0U) +#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ +#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ +#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ +#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ +#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ +#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ +#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ +#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ +#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ +#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ +#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ +#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ +#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ +#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ +#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ +#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ +#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ +#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ +#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ +#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ +#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ +#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ +#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ +#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ +#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ +#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ +#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ +#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ + +#define ADC_OFR4_OFFSET4_CH_Pos (26U) +#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ +#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR4_SSATE_Pos (31U) +#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ +#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ + +#define ADC3_OFR4_OFFSET4_Pos (0U) +#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ +#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ + +#define ADC3_OFR4_OFFSETPOS_Pos (24U) +#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ +#define ADC3_OFR4_SATEN_Pos (25U) +#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ +#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ + +#define ADC3_OFR4_OFFSET4_EN_Pos (31U) +#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ +#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ + +/******************** Bit definition for ADC_JDR1 register ********************/ +#define ADC_JDR1_JDATA_Pos (0U) +#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR2 register ********************/ +#define ADC_JDR2_JDATA_Pos (0U) +#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR3 register ********************/ +#define ADC_JDR3_JDATA_Pos (0U) +#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_JDR4 register ********************/ +#define ADC_JDR4_JDATA_Pos (0U) +#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ +#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ +#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ +#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ +#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ +#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ +#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ +#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ +#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ +#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ +#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ +#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ +#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ +#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ +#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ +#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ +#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ +#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ +#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ +#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ +#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ +#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ +#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ +#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ +#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ +#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ +#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ +#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ +#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ +#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ +#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ +#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ +#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ +#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_AWD2CR register ********************/ +#define ADC_AWD2CR_AWD2CH_Pos (0U) +#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ +#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ +#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ +#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_AWD3CR register ********************/ +#define ADC_AWD3CR_AWD3CH_Pos (0U) +#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ +#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ +#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ +#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_DIFSEL register ********************/ +#define ADC_DIFSEL_DIFSEL_Pos (0U) +#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ +#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ +#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ +#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ +#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ +#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ +#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ +#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ +#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ +#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ +#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ +#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ +#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ +#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ +#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ +#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ +#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ +#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ +#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ +#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ +#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ +#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ + +/******************** Bit definition for ADC_CALFACT register ********************/ +#define ADC_CALFACT_CALFACT_S_Pos (0U) +#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ +#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ +#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ +#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ +#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ +#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ +#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ +#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ +#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ +#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ +#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ +#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ +#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ +#define ADC_CALFACT_CALFACT_D_Pos (16U) +#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ +#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ +#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ +#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ +#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ +#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ +#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ +#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ +#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ +#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ +#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ +#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ +#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ + +/******************** Bit definition for ADC_CALFACT2 register ********************/ +#define ADC_CALFACT2_LINCALFACT_Pos (0U) +#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ +#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ +#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ +#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ +#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ +#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ +#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ +#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ +#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ +#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ +#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ +#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ +#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ +#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ +#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ +#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ +#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ +#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ +#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ +#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ +#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ +#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ +#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ +#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ +#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ +#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ +#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ +#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ +#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ +#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ +#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ +#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ + +/************************* ADC Common registers *****************************/ +/******************** Bit definition for ADC_CSR register ********************/ +#define ADC_CSR_ADRDY_MST_Pos (0U) +#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ +#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ +#define ADC_CSR_EOSMP_MST_Pos (1U) +#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ +#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ +#define ADC_CSR_EOC_MST_Pos (2U) +#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ +#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ +#define ADC_CSR_EOS_MST_Pos (3U) +#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ +#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ +#define ADC_CSR_OVR_MST_Pos (4U) +#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ +#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ +#define ADC_CSR_JEOC_MST_Pos (5U) +#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ +#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ +#define ADC_CSR_JEOS_MST_Pos (6U) +#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ +#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ +#define ADC_CSR_AWD1_MST_Pos (7U) +#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ +#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ +#define ADC_CSR_AWD2_MST_Pos (8U) +#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ +#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ +#define ADC_CSR_AWD3_MST_Pos (9U) +#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ +#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ +#define ADC_CSR_JQOVF_MST_Pos (10U) +#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ +#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ +#define ADC_CSR_ADRDY_SLV_Pos (16U) +#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ +#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ +#define ADC_CSR_EOSMP_SLV_Pos (17U) +#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ +#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ +#define ADC_CSR_EOC_SLV_Pos (18U) +#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ +#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ +#define ADC_CSR_EOS_SLV_Pos (19U) +#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ +#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ +#define ADC_CSR_OVR_SLV_Pos (20U) +#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ +#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ +#define ADC_CSR_JEOC_SLV_Pos (21U) +#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ +#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ +#define ADC_CSR_JEOS_SLV_Pos (22U) +#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ +#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ +#define ADC_CSR_AWD1_SLV_Pos (23U) +#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ +#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ +#define ADC_CSR_AWD2_SLV_Pos (24U) +#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ +#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ +#define ADC_CSR_AWD3_SLV_Pos (25U) +#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ +#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ +#define ADC_CSR_JQOVF_SLV_Pos (26U) +#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ +#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ + +/******************** Bit definition for ADC_CCR register ********************/ +#define ADC_CCR_DUAL_Pos (0U) +#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ +#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ +#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ +#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ +#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ +#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ +#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ + +#define ADC_CCR_DELAY_Pos (8U) +#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ +#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ +#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ +#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ +#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ +#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ + + +#define ADC_CCR_DAMDF_Pos (14U) +#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ +#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ +#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ +#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ + +#define ADC_CCR_CKMODE_Pos (16U) +#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ +#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ +#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ +#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ + +#define ADC_CCR_PRESC_Pos (18U) +#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ +#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ +#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ +#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ +#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ +#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ + +#define ADC_CCR_VREFEN_Pos (22U) +#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ +#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ +#define ADC_CCR_TSEN_Pos (23U) +#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ +#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ +#define ADC_CCR_VBATEN_Pos (24U) +#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ +#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ + +/******************** Bit definition for ADC_CDR register *******************/ +#define ADC_CDR_RDATA_MST_Pos (0U) +#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ +#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ + +#define ADC_CDR_RDATA_SLV_Pos (16U) +#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ +#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ + +/******************** Bit definition for ADC_CDR2 register ******************/ +#define ADC_CDR2_RDATA_ALT_Pos (0U) +#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ +#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ + + +/******************************************************************************/ +/* */ +/* VREFBUF */ +/* */ +/******************************************************************************/ +/******************* Bit definition for VREFBUF_CSR register ****************/ +#define VREFBUF_CSR_ENVR_Pos (0U) +#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ +#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ +#define DAC_CR_CEN1_Pos (14U) +#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ +#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ + +#define DAC_CR_EN2_Pos (16U) +#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ +#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ +#define DAC_CR_CEN2_Pos (30U) +#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ +#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ + +/***************** Bit definition for DAC_SWTRIGR register ******************/ +#define DAC_SWTRIGR_SWTRIG1_Pos (0U) +#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ +#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_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 stm32h7xx + * @{ + */ + +#ifndef STM32H7xx_H +#define STM32H7xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/** + * @brief STM32 Family + */ +#if !defined (STM32H7) +#define STM32H7 +#endif /* STM32H7 */ + + +/* Uncomment the line below according to the target STM32H7 device used in your + application + */ + +/* #if !defined (STM32H743xx) && !defined (STM32H753xx) && !defined (STM32H750xx) && !defined (STM32H742xx) && \ + !defined (STM32H745xx) && !defined (STM32H755xx) && !defined (STM32H747xx) && !defined (STM32H757xx) && \ + !defined (STM32H7A3xx) && !defined (STM32H7A3xxQ) && !defined (STM32H7B3xx) && !defined (STM32H7B3xxQ) && !defined (STM32H7B0xx) && !defined (STM32H7B0xxQ) && \ + !defined (STM32H735xx) && !defined (STM32H733xx) && !defined (STM32H730xx) && !defined (STM32H730xxQ) && !defined (STM32H725xx) && !defined (STM32H723xx) */ + /* #define STM32H742xx */ /*!< STM32H742VI, STM32H742ZI, STM32H742AI, STM32H742II, STM32H742BI, STM32H742XI Devices */ + /* #define STM32H743xx */ /*!< STM32H743VI, STM32H743ZI, STM32H743AI, STM32H743II, STM32H743BI, STM32H743XI Devices */ + /* #define STM32H753xx */ /*!< STM32H753VI, STM32H753ZI, STM32H753AI, STM32H753II, STM32H753BI, STM32H753XI Devices */ + /* #define STM32H750xx */ /*!< STM32H750V, STM32H750I, STM32H750X Devices */ + /* #define STM32H747xx */ /*!< STM32H747ZI, STM32H747AI, STM32H747II, STM32H747BI, STM32H747XI Devices */ + /* #define STM32H757xx */ /*!< STM32H757ZI, STM32H757AI, STM32H757II, STM32H757BI, STM32H757XI Devices */ + /* #define STM32H745xx */ /*!< STM32H745ZI, STM32H745II, STM32H745BI, STM32H745XI Devices */ + /* #define STM32H755xx */ /*!< STM32H755ZI, STM32H755II, STM32H755BI, STM32H755XI Devices */ + /* #define STM32H7B0xx */ /*!< STM32H7B0ABIxQ, STM32H7B0IBTx, STM32H7B0RBTx, STM32H7B0VBTx, STM32H7B0ZBTx, STM32H7B0IBKxQ */ + /* #define STM32H7A3xx */ /*!< STM32H7A3IIK6, STM32H7A3IIT6, STM32H7A3NIH6, STM32H7A3RIT6, STM32H7A3VIH6, STM32H7A3VIT6, STM32H7A3ZIT6 */ + /* #define STM32H7A3xxQ */ /*!< STM32H7A3QIY6Q, STM32H7A3IIK6Q, STM32H7A3IIT6Q, STM32H7A3LIH6Q, STM32H7A3VIH6Q, STM32H7A3VIT6Q, STM32H7A3AII6Q, STM32H7A3ZIT6Q */ + /* #define STM32H7B3xx */ /*!< STM32H7B3IIK6, STM32H7B3IIT6, STM32H7B3NIH6, STM32H7B3RIT6, STM32H7B3VIH6, STM32H7B3VIT6, STM32H7B3ZIT6 */ + /* #define STM32H7B3xxQ */ /*!< STM32H7B3QIY6Q, STM32H7B3IIK6Q, STM32H7B3IIT6Q, STM32H7B3LIH6Q, STM32H7B3VIH6Q, STM32H7B3VIT6Q, STM32H7B3AII6Q, STM32H7B3ZIT6Q */ + /* #define STM32H735xx */ /*!< STM32H735AGI6, STM32H735IGK6, STM32H735RGV6, STM32H735VGT6, STM32H735VGY6, STM32H735ZGT6 Devices */ + /* #define STM32H733xx */ /*!< STM32H733VGH6, STM32H733VGT6, STM32H733ZGI6, STM32H733ZGT6, Devices */ + /* #define STM32H730xx */ /*!< STM32H730VBH6, STM32H730VBT6, STM32H730ZBT6, STM32H730ZBI6 Devices */ + /* #define STM32H730xxQ */ /*!< STM32H730IBT6Q, STM32H730ABI6Q, STM32H730IBK6Q Devices */ + /* #define STM32H725xx */ /*!< STM32H725AGI6, STM32H725IGK6, STM32H725IGT6, STM32H725RGV6, STM32H725VGT6, STM32H725VGY6, STM32H725ZGT6, STM32H725REV6, SM32H725VET6, STM32H725ZET6, STM32H725AEI6, STM32H725IET6, STM32H725IEK6 Devices */ + /* #define STM32H723xx */ /*!< STM32H723VGH6, STM32H723VGT6, STM32H723ZGI6, STM32H723ZGT6, STM32H723VET6, STM32H723VEH6, STM32H723ZET6, STM32H723ZEI6 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(DUAL_CORE) && !defined(CORE_CM4) && !defined(CORE_CM7) + #error "Dual core device, please select CORE_CM4 or CORE_CM7" +#endif + +#if !defined (USE_HAL_DRIVER) +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_HAL_DRIVER */ +#endif /* USE_HAL_DRIVER */ + +/** + * @brief CMSIS Device version number V1.10.0 + */ +#define __STM32H7xx_CMSIS_DEVICE_VERSION_MAIN (0x01) /*!< [31:24] main version */ +#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 (0x0A) /*!< [23:16] sub1 version */ +#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32H7xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32H7xx_CMSIS_DEVICE_VERSION ((__STM32H7xx_CMSIS_DEVICE_VERSION_MAIN << 24)\ + |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 << 16)\ + |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 << 8 )\ + |(__STM32H7xx_CMSIS_DEVICE_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Device_Included + * @{ + */ + +#if defined(STM32H743xx) + #include "stm32h743xx.h" +// #elif defined(STM32H753xx) +// #include "stm32h753xx.h" +// #elif defined(STM32H750xx) +// #include "stm32h750xx.h" +// #elif defined(STM32H742xx) +// #include "stm32h742xx.h" +// #elif defined(STM32H745xx) +// #include "stm32h745xx.h" +// #elif defined(STM32H755xx) +// #include "stm32h755xx.h" +// #elif defined(STM32H747xx) +// #include "stm32h747xx.h" +// #elif defined(STM32H757xx) +// #include "stm32h757xx.h" +// #elif defined(STM32H7B0xx) +// #include "stm32h7b0xx.h" +// #elif defined(STM32H7B0xxQ) +// #include "stm32h7b0xxq.h" +// #elif defined(STM32H7A3xx) +// #include "stm32h7a3xx.h" +// #elif defined(STM32H7B3xx) +// #include "stm32h7b3xx.h" +// #elif defined(STM32H7A3xxQ) +// #include "stm32h7a3xxq.h" +// #elif defined(STM32H7B3xxQ) +// #include "stm32h7b3xxq.h" +#elif defined(STM32H735xx) + #include "stm32h735xx.h" +// #elif defined(STM32H733xx) +// #include "stm32h733xx.h" +// #elif defined(STM32H730xx) +// #include "stm32h730xx.h" +// #elif defined(STM32H730xxQ) +// #include "stm32h730xxq.h" +#elif defined(STM32H725xx) + #include "stm32h725xx.h" +// #elif defined(STM32H723xx) +// #include "stm32h723xx.h" +#else + #error "Please select first the target STM32H7xx device used in your application (in stm32h7xx.h file)" +#endif + +/** + * @} + */ + +/** @addtogroup Exported_types + * @{ + */ +typedef enum +{ + RESET = 0, + SET = !RESET +} FlagStatus, ITStatus; + +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum +{ + SUCCESS = 0, + ERROR = !SUCCESS +} ErrorStatus; + +/** + * @} + */ + + +/** @addtogroup Exported_macros + * @{ + */ +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + +#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) + + +/** + * @} + */ + +#if defined (USE_HAL_DRIVER) + #include "stm32h7xx_hal.h" +#endif /* USE_HAL_DRIVER */ + + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* STM32H7xx_H */ +/** + * @} + */ + +/** + * @} + */ + + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_def.h b/panda/board/stm32h7/inc/stm32h7xx_hal_def.h new file mode 100644 index 000000000..3854b1cd3 --- /dev/null +++ b/panda/board/stm32h7/inc/stm32h7xx_hal_def.h @@ -0,0 +1,221 @@ +/** + ****************************************************************************** + * @file stm32h7xx_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 STM32H7xx_HAL_DEF +#define STM32H7xx_HAL_DEF + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32h7xx.h" +//#include "Legacy/stm32_hal_legacy.h" +//#include +//#include + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief HAL Status structures definition + */ +typedef enum +{ + HAL_OK = 0x00, + HAL_ERROR = 0x01, + HAL_BUSY = 0x02, + HAL_TIMEOUT = 0x03 +} HAL_StatusTypeDef; + +/** + * @brief HAL Lock structures definition + */ +typedef enum +{ + HAL_UNLOCKED = 0x00, + HAL_LOCKED = 0x01 +} HAL_LockTypeDef; + +/* Exported macro ------------------------------------------------------------*/ + +#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(0) + +#define UNUSED(x) ((void)(x)) + +/** @brief Reset the Handle's State field. + * @param __HANDLE__: specifies the Peripheral Handle. + * @note This macro can be used for the following purpose: + * - When the Handle is declared as local variable; before passing it as parameter + * to HAL_PPP_Init() for the first time, it is mandatory to use this macro + * to set to 0 the Handle's "State" field. + * Otherwise, "State" field may have any random value and the first time the function + * HAL_PPP_Init() is called, the low level hardware initialization will be missed + * (i.e. HAL_PPP_MspInit() will not be executed). + * - When there is a need to reconfigure the low level hardware: instead of calling + * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). + * In this later function, when the Handle's "State" field is set to 0, it will execute the function + * HAL_PPP_MspInit() which will reconfigure the low level hardware. + * @retval None + */ +#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0) + +#if (USE_RTOS == 1) + #error " USE_RTOS should be 0 in the current HAL release " +#else + #define __HAL_LOCK(__HANDLE__) \ + do{ \ + if((__HANDLE__)->Lock == HAL_LOCKED) \ + { \ + return HAL_BUSY; \ + } \ + else \ + { \ + (__HANDLE__)->Lock = HAL_LOCKED; \ + } \ + }while (0) + + #define __HAL_UNLOCK(__HANDLE__) \ + do{ \ + (__HANDLE__)->Lock = HAL_UNLOCKED; \ + }while (0) +#endif /* USE_RTOS */ + + +#if defined (__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__ */ + +/* Macro to get variable aligned on 32-bytes,needed for cache maintenance purpose */ +#if defined (__GNUC__) /* GNU Compiler */ + #define ALIGN_32BYTES(buf) buf __attribute__ ((aligned (32))) +#elif defined (__ICCARM__) /* IAR Compiler */ + #define ALIGN_32BYTES(buf) _Pragma("data_alignment=32") buf +#elif defined (__CC_ARM) /* ARM Compiler */ + #define ALIGN_32BYTES(buf) __align(32) buf +#endif + +/** + * @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 /* STM32H7xx_HAL_DEF */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h b/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h new file mode 100644 index 000000000..14f576a42 --- /dev/null +++ b/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h @@ -0,0 +1,489 @@ +/** + ****************************************************************************** + * @file stm32h7xx_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 STM32H7xx_HAL_GPIO_EX_H +#define STM32H7xx_HAL_GPIO_EX_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32h7xx_hal_def.h" + +/** @addtogroup STM32H7xx_HAL_Driver + * @{ + */ + +/** @addtogroup GPIOEx GPIOEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants + * @{ + */ + +/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection + * @{ + */ + +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)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_LCDBIAS ((uint8_t)0x00) /* LCDBIAS Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ +#if defined (PWR_CPUCR_PDDS_D2) /* PWR D1 and D2 domains exists */ +#define GPIO_AF0_C1DSLEEP ((uint8_t)0x00) /* Cortex-M7 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ +#define GPIO_AF0_C1SLEEP ((uint8_t)0x00) /* Cortex-M7 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ +#define GPIO_AF0_D1PWREN ((uint8_t)0x00) /* Domain 1 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ +#define GPIO_AF0_D2PWREN ((uint8_t)0x00) /* Domain 2 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ +#if defined(DUAL_CORE) +#define GPIO_AF0_C2DSLEEP ((uint8_t)0x00) /* Cortex-M4 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ +#define GPIO_AF0_C2SLEEP ((uint8_t)0x00) /* Cortex-M4 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ +#endif /* DUAL_CORE */ +#endif /* PWR_CPUCR_PDDS_D2 */ + +/** + * @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_TIM16 ((uint8_t)0x01) /* TIM16 Alternate Function mapping */ +#define GPIO_AF1_TIM17 ((uint8_t)0x01) /* TIM17 Alternate Function mapping */ +#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ +#if defined(HRTIM1) +#define GPIO_AF1_HRTIM1 ((uint8_t)0x01) /* HRTIM1 Alternate Function mapping */ +#endif /* HRTIM1 */ +#if defined(SAI4) +#define GPIO_AF1_SAI4 ((uint8_t)0x01) /* SAI4 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ +#endif /* SAI4 */ +#define GPIO_AF1_FMC ((uint8_t)0x01) /* FMC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ + + +/** + * @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 */ +#define GPIO_AF2_TIM12 ((uint8_t)0x02) /* TIM12 Alternate Function mapping */ +#define GPIO_AF2_SAI1 ((uint8_t)0x02) /* SAI1 Alternate Function mapping */ +#if defined(HRTIM1) +#define GPIO_AF2_HRTIM1 ((uint8_t)0x02) /* HRTIM1 Alternate Function mapping */ +#endif /* HRTIM1 */ +#define GPIO_AF2_TIM15 ((uint8_t)0x02) /* TIM15 Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ +#if defined(FDCAN3) +#define GPIO_AF2_FDCAN3 ((uint8_t)0x02) /* FDCAN3 Alternate Function mapping */ +#endif /*FDCAN3*/ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_LPTIM2 ((uint8_t)0x03) /* LPTIM2 Alternate Function mapping */ +#define GPIO_AF3_DFSDM1 ((uint8_t)0x03) /* DFSDM Alternate Function mapping */ +#define GPIO_AF3_LPTIM3 ((uint8_t)0x03) /* LPTIM3 Alternate Function mapping */ +#define GPIO_AF3_LPTIM4 ((uint8_t)0x03) /* LPTIM4 Alternate Function mapping */ +#define GPIO_AF3_LPTIM5 ((uint8_t)0x03) /* LPTIM5 Alternate Function mapping */ +#define GPIO_AF3_LPUART ((uint8_t)0x03) /* LPUART Alternate Function mapping */ +#if defined(OCTOSPIM) +#define GPIO_AF3_OCTOSPIM_P1 ((uint8_t)0x03) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#define GPIO_AF3_OCTOSPIM_P2 ((uint8_t)0x03) /* OCTOSPI Manager Port 2 Alternate Function mapping */ +#endif /* OCTOSPIM */ +#if defined(HRTIM1) +#define GPIO_AF3_HRTIM1 ((uint8_t)0x03) /* HRTIM1 Alternate Function mapping */ +#endif /* HRTIM1 */ +#define GPIO_AF3_LTDC ((uint8_t)0x03) /* LTDC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ + +/** + * @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_I2C4 ((uint8_t)0x04) /* I2C4 Alternate Function mapping */ +#if defined(I2C5) +#define GPIO_AF4_I2C5 ((uint8_t)0x04) /* I2C5 Alternate Function mapping */ +#endif /* I2C5*/ +#define GPIO_AF4_TIM15 ((uint8_t)0x04) /* TIM15 Alternate Function mapping */ +#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ +#define GPIO_AF4_LPTIM2 ((uint8_t)0x04) /* LPTIM2 Alternate Function mapping */ +#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */ +#if defined(USART10) +#define GPIO_AF4_USART10 ((uint8_t)0x04) /* USART10 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ +#endif /*USART10*/ +#define GPIO_AF4_DFSDM1 ((uint8_t)0x04) /* DFSDM Alternate Function mapping */ +#if defined(DFSDM2_BASE) +#define GPIO_AF4_DFSDM2 ((uint8_t)0x04) /* DFSDM2 Alternate Function mapping */ +#endif /* DFSDM2_BASE */ +#define GPIO_AF4_DCMI ((uint8_t)0x04) /* DCMI Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ +#if defined(PSSI) +#define GPIO_AF4_PSSI ((uint8_t)0x04) /* PSSI Alternate Function mapping */ +#endif /* PSSI */ +#if defined(OCTOSPIM) +#define GPIO_AF4_OCTOSPIM_P1 ((uint8_t)0x04) /* OCTOSPI Manager Port 1 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ +#endif /* OCTOSPIM */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 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_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ +#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ +#define GPIO_AF5_CEC ((uint8_t)0x05) /* CEC Alternate Function mapping */ +#if defined(FDCAN3) +#define GPIO_AF5_FDCAN3 ((uint8_t)0x05) /* FDCAN3 Alternate Function mapping */ +#endif /*FDCAN3*/ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2 Alternate Function mapping */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3 Alternate Function mapping */ +#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ +#define GPIO_AF6_I2C4 ((uint8_t)0x06) /* I2C4 Alternate Function mapping */ +#if defined(I2C5) +#define GPIO_AF6_I2C5 ((uint8_t)0x06) /* I2C5 Alternate Function mapping */ +#endif /* I2C5*/ +#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM Alternate Function mapping */ +#define GPIO_AF6_UART4 ((uint8_t)0x06) /* UART4 Alternate Function mapping */ +#if defined(DFSDM2_BASE) +#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ +#endif /* DFSDM2_BASE */ +#if defined(SAI3) +#define GPIO_AF6_SAI3 ((uint8_t)0x06) /* SAI3 Alternate Function mapping */ +#endif /* SAI3 */ +#if defined(OCTOSPIM) +#define GPIO_AF6_OCTOSPIM_P1 ((uint8_t)0x06) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#endif /* OCTOSPIM */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2 Alternate Function mapping */ +#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3 Alternate Function mapping */ +#define GPIO_AF7_SPI6 ((uint8_t)0x07) /* SPI6 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_USART6 ((uint8_t)0x07) /* USART6 Alternate Function mapping */ +#define GPIO_AF7_UART7 ((uint8_t)0x07) /* UART7 Alternate Function mapping */ +#define GPIO_AF7_SDMMC1 ((uint8_t)0x07) /* SDMMC1 Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_SPI6 ((uint8_t)0x08) /* SPI6 Alternate Function mapping */ +#if defined(SAI2) +#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ +#endif /*SAI2*/ +#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_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ +#define GPIO_AF8_SPDIF ((uint8_t)0x08) /* SPDIF Alternate Function mapping */ +#define GPIO_AF8_LPUART ((uint8_t)0x08) /* LPUART Alternate Function mapping */ +#define GPIO_AF8_SDMMC1 ((uint8_t)0x08) /* SDMMC1 Alternate Function mapping */ +#if defined(SAI4) +#define GPIO_AF8_SAI4 ((uint8_t)0x08) /* SAI4 Alternate Function mapping */ +#endif /* SAI4 */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_FDCAN1 ((uint8_t)0x09) /* FDCAN1 Alternate Function mapping */ +#define GPIO_AF9_FDCAN2 ((uint8_t)0x09) /* FDCAN2 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_SDMMC2 ((uint8_t)0x09) /* SDMMC2 Alternate Function mapping */ +#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LTDC Alternate Function mapping */ +#define GPIO_AF9_SPDIF ((uint8_t)0x09) /* SPDIF Alternate Function mapping */ +#define GPIO_AF9_FMC ((uint8_t)0x09) /* FMC Alternate Function mapping */ +#if defined(QUADSPI) +#define GPIO_AF9_QUADSPI ((uint8_t)0x09) /* QUADSPI Alternate Function mapping */ +#endif /* QUADSPI */ +#if defined(SAI4) +#define GPIO_AF9_SAI4 ((uint8_t)0x09) /* SAI4 Alternate Function mapping */ +#endif /* SAI4 */ +#if defined(OCTOSPIM) +#define GPIO_AF9_OCTOSPIM_P1 ((uint8_t)0x09) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#define GPIO_AF9_OCTOSPIM_P2 ((uint8_t)0x09) /* OCTOSPI Manager Port 2 Alternate Function mapping */ +#endif /* OCTOSPIM */ + +/** + * @brief AF 10 selection + */ +#if defined(SAI2) +#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ +#endif /*SAI2*/ +#define GPIO_AF10_SDMMC2 ((uint8_t)0x0A) /* SDMMC2 Alternate Function mapping */ +#if defined(USB2_OTG_FS) +#define GPIO_AF10_OTG2_FS ((uint8_t)0x0A) /* OTG2_FS Alternate Function mapping */ +#endif /*USB2_OTG_FS*/ +#define GPIO_AF10_COMP1 ((uint8_t)0x0A) /* COMP1 Alternate Function mapping */ +#define GPIO_AF10_COMP2 ((uint8_t)0x0A) /* COMP2 Alternate Function mapping */ +#if defined(LTDC) +#define GPIO_AF10_LTDC ((uint8_t)0x0A) /* LTDC Alternate Function mapping */ +#endif /*LTDC*/ +#define GPIO_AF10_CRS_SYNC ((uint8_t)0x0A) /* CRS Sync Alternate Function mapping : available on STM32H7 Rev.B and above */ +#if defined(QUADSPI) +#define GPIO_AF10_QUADSPI ((uint8_t)0x0A) /* QUADSPI Alternate Function mapping */ +#endif /* QUADSPI */ +#if defined(SAI4) +#define GPIO_AF10_SAI4 ((uint8_t)0x0A) /* SAI4 Alternate Function mapping */ +#endif /* SAI4 */ +#if !defined(USB2_OTG_FS) +#define GPIO_AF10_OTG1_FS ((uint8_t)0x0A) /* OTG1_FS Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ +#endif /* !USB2_OTG_FS */ +#define GPIO_AF10_OTG1_HS ((uint8_t)0x0A) /* OTG1_HS Alternate Function mapping */ +#if defined(OCTOSPIM) +#define GPIO_AF10_OCTOSPIM_P1 ((uint8_t)0x0A) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#endif /* OCTOSPIM */ +#define GPIO_AF10_TIM8 ((uint8_t)0x0A) /* TIM8 Alternate Function mapping */ +#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF11_SWP ((uint8_t)0x0B) /* SWP Alternate Function mapping */ +#define GPIO_AF11_MDIOS ((uint8_t)0x0B) /* MDIOS Alternate Function mapping */ +#define GPIO_AF11_UART7 ((uint8_t)0x0B) /* UART7 Alternate Function mapping */ +#define GPIO_AF11_SDMMC2 ((uint8_t)0x0B) /* SDMMC2 Alternate Function mapping */ +#define GPIO_AF11_DFSDM1 ((uint8_t)0x0B) /* DFSDM1 Alternate Function mapping */ +#define GPIO_AF11_COMP1 ((uint8_t)0x0B) /* COMP1 Alternate Function mapping */ +#define GPIO_AF11_COMP2 ((uint8_t)0x0B) /* COMP2 Alternate Function mapping */ +#define GPIO_AF11_TIM1 ((uint8_t)0x0B) /* TIM1 Alternate Function mapping */ +#define GPIO_AF11_TIM8 ((uint8_t)0x0B) /* TIM8 Alternate Function mapping */ +#define GPIO_AF11_I2C4 ((uint8_t)0x0B) /* I2C4 Alternate Function mapping */ +#if defined(DFSDM2_BASE) +#define GPIO_AF11_DFSDM2 ((uint8_t)0x0B) /* DFSDM2 Alternate Function mapping */ +#endif /* DFSDM2_BASE */ +#if defined(USART10) +#define GPIO_AF11_USART10 ((uint8_t)0x0B) /* USART10 Alternate Function mapping */ +#endif /* USART10 */ +#if defined(UART9) +#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ +#endif /* UART9 */ +#if defined(ETH) +#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETH Alternate Function mapping */ +#endif /* ETH */ +#if defined(LTDC) +#define GPIO_AF11_LTDC ((uint8_t)0x0B) /* LTDC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ +#endif /*LTDC*/ +#if defined(OCTOSPIM) +#define GPIO_AF11_OCTOSPIM_P1 ((uint8_t)0x0B) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#endif /* OCTOSPIM */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ +#define GPIO_AF12_SDMMC1 ((uint8_t)0x0C) /* SDMMC1 Alternate Function mapping */ +#define GPIO_AF12_MDIOS ((uint8_t)0x0C) /* MDIOS Alternate Function mapping */ +#define GPIO_AF12_COMP1 ((uint8_t)0x0C) /* COMP1 Alternate Function mapping */ +#define GPIO_AF12_COMP2 ((uint8_t)0x0C) /* COMP2 Alternate Function mapping */ +#define GPIO_AF12_TIM1 ((uint8_t)0x0C) /* TIM1 Alternate Function mapping */ +#define GPIO_AF12_TIM8 ((uint8_t)0x0C) /* TIM8 Alternate Function mapping */ +#if defined(LTDC) +#define GPIO_AF12_LTDC ((uint8_t)0x0C) /* LTDC Alternate Function mapping */ +#endif /*LTDC*/ +#if defined(USB2_OTG_FS) +#define GPIO_AF12_OTG1_FS ((uint8_t)0x0C) /* OTG1_FS Alternate Function mapping */ +#endif /* USB2_OTG_FS */ +#if defined(OCTOSPIM) +#define GPIO_AF12_OCTOSPIM_P1 ((uint8_t)0x0C) /* OCTOSPI Manager Port 1 Alternate Function mapping */ +#endif /* OCTOSPIM */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ +#define GPIO_AF13_COMP1 ((uint8_t)0x0D) /* COMP1 Alternate Function mapping */ +#define GPIO_AF13_COMP2 ((uint8_t)0x0D) /* COMP2 Alternate Function mapping */ +#if defined(LTDC) +#define GPIO_AF13_LTDC ((uint8_t)0x0D) /* LTDC Alternate Function mapping */ +#endif /*LTDC*/ +#if defined(DSI) +#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ +#endif /* DSI */ +#if defined(PSSI) +#define GPIO_AF13_PSSI ((uint8_t)0x0D) /* PSSI Alternate Function mapping */ +#endif /* PSSI */ +#define GPIO_AF13_TIM1 ((uint8_t)0x0D) /* TIM1 Alternate Function mapping */ +#if defined(TIM23) +#define GPIO_AF13_TIM23 ((uint8_t)0x0D) /* TIM23 Alternate Function mapping */ +#endif /*TIM23*/ + +/** + * @brief AF 14 selection + */ +#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LTDC Alternate Function mapping */ +#define GPIO_AF14_UART5 ((uint8_t)0x0E) /* UART5 Alternate Function mapping */ +#if defined(TIM24) +#define GPIO_AF14_TIM24 ((uint8_t)0x0E) /* TIM24 Alternate Function mapping */ +#endif /*TIM24*/ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ + +#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x0F) + + + +/** + * @} + */ + +/** + * @} + */ + +/* 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 + * @{ + */ + +/** + * @brief GPIO pin available on the platform + */ +/* Defines the available pins per GPIOs */ +#define GPIOA_PIN_AVAILABLE GPIO_PIN_All +#define GPIOB_PIN_AVAILABLE GPIO_PIN_All +#define GPIOC_PIN_AVAILABLE GPIO_PIN_All +#define GPIOD_PIN_AVAILABLE GPIO_PIN_All +#define GPIOE_PIN_AVAILABLE GPIO_PIN_All +#define GPIOF_PIN_AVAILABLE GPIO_PIN_All +#define GPIOG_PIN_AVAILABLE GPIO_PIN_All +#if defined(GPIOI) +#define GPIOI_PIN_AVAILABLE GPIO_PIN_All +#endif /*GPIOI*/ +#if defined(GPIOI) +#define GPIOJ_PIN_AVAILABLE GPIO_PIN_All +#else +#define GPIOJ_PIN_AVAILABLE (GPIO_PIN_8 | GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11 ) +#endif /* GPIOI */ +#define GPIOH_PIN_AVAILABLE GPIO_PIN_All +#if defined(GPIOI) +#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 | \ + GPIO_PIN_5 | GPIO_PIN_6 | GPIO_PIN_7) +#else +#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 ) +#endif /* GPIOI */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Macros GPIO Private Macros + * @{ + */ +/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index + * @{ + */ +#if defined(GPIOI) +#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ + ((__GPIOx__) == (GPIOB))? 1UL :\ + ((__GPIOx__) == (GPIOC))? 2UL :\ + ((__GPIOx__) == (GPIOD))? 3UL :\ + ((__GPIOx__) == (GPIOE))? 4UL :\ + ((__GPIOx__) == (GPIOF))? 5UL :\ + ((__GPIOx__) == (GPIOG))? 6UL :\ + ((__GPIOx__) == (GPIOH))? 7UL :\ + ((__GPIOx__) == (GPIOI))? 8UL :\ + ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) +#else +#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ + ((__GPIOx__) == (GPIOB))? 1UL :\ + ((__GPIOx__) == (GPIOC))? 2UL :\ + ((__GPIOx__) == (GPIOD))? 3UL :\ + ((__GPIOx__) == (GPIOE))? 4UL :\ + ((__GPIOx__) == (GPIOF))? 5UL :\ + ((__GPIOx__) == (GPIOG))? 6UL :\ + ((__GPIOx__) == (GPIOH))? 7UL :\ + ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) +#endif /* GPIOI */ + +/** + * @} + */ + +/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function + * @{ + */ +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Functions GPIO Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32H7xx_HAL_GPIO_EX_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/system_stm32h7xx.h b/panda/board/stm32h7/inc/system_stm32h7xx.h new file mode 100644 index 000000000..dd75af67f --- /dev/null +++ b/panda/board/stm32h7/inc/system_stm32h7xx.h @@ -0,0 +1,105 @@ +/** + ****************************************************************************** + * @file system_stm32h7xx.h + * @author MCD Application Team + * @brief CMSIS Cortex-Mx Device System Source File for STM32H7xx devices. + ****************************************************************************** + * @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 stm32h7xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef SYSTEM_STM32H7XX_H +#define SYSTEM_STM32H7XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32H7xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32H7xx_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 Domain1 Clock Frequency */ +extern uint32_t SystemD2Clock; /*!< System Domain2 Clock Frequency */ +extern const uint8_t D1CorePrescTable[16] ; /*!< D1CorePrescTable prescalers table values */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* SYSTEM_STM32H7XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/interrupt_handlers.h b/panda/board/stm32h7/interrupt_handlers.h new file mode 100644 index 000000000..2b0a2b428 --- /dev/null +++ b/panda/board/stm32h7/interrupt_handlers.h @@ -0,0 +1,74 @@ +// ********************* Bare interrupt handlers ********************* +// Interrupts for STM32H7x5 + +void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} +void PVD_AVD_IRQHandler(void) {handle_interrupt(PVD_AVD_IRQn);} +void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} +void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} +void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} +void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} +void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} +void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} +void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} +void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} +void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} +void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} +void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} +void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} +void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} +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 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);} +void TIM1_TRG_COM_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_IRQn);} +void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} +void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} +void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} +void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} +void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} +void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} +void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} +void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} +void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} +void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} +void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} +void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} +void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} +void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} +void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} +void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} +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 TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} +void SPI3_IRQHandler(void) {handle_interrupt(SPI3_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);} +void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} +void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} +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 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);} diff --git a/panda/board/stm32h7/lladc.h b/panda/board/stm32h7/lladc.h new file mode 100644 index 000000000..795ca3533 --- /dev/null +++ b/panda/board/stm32h7/lladc.h @@ -0,0 +1,48 @@ +// 5VOUT_S = ADC12_INP5 +// VOLT_S = ADC1_INP2 +#define ADCCHAN_VOLTAGE 2 + +void adc_init(void) { + ADC1->CR &= ~(ADC_CR_DEEPPWD); //Reset deep-power-down mode + ADC1->CR |= ADC_CR_ADVREGEN; // Enable ADC regulator + while(!(ADC1->ISR & ADC_ISR_LDORDY)); + + ADC1->CR &= ~(ADC_CR_ADCALDIF); // Choose single-ended calibration + ADC1->CR |= ADC_CR_ADCALLIN; // Lineriality calibration + ADC1->CR |= ADC_CR_ADCAL; // Start calibrtation + while((ADC1->CR & ADC_CR_ADCAL) != 0); + + ADC1->ISR |= ADC_ISR_ADRDY; + ADC1->CR |= ADC_CR_ADEN; + while(!(ADC1->ISR & ADC_ISR_ADRDY)); +} + +uint32_t adc_get(unsigned int channel) { + + ADC1->SQR1 &= ~(ADC_SQR1_L); + ADC1->SQR1 = (channel << 6U); + + ADC1->SMPR1 = (0x7U << (channel * 3U) ); + ADC1->PCSEL_RES0 = (0x1U << channel); + + ADC1->CR |= ADC_CR_ADSTART; + while (!(ADC1->ISR & ADC_ISR_EOC)); + + uint16_t res = ADC1->DR; + + while (!(ADC1->ISR & ADC_ISR_EOS)); + ADC1->ISR |= ADC_ISR_EOS; + + return res; +} + +uint32_t adc_get_voltage(void) { + // REVC has a 10, 1 (1/11) voltage divider + // Here is the calculation for the scale (s) + // ADCV = VIN_S * (1/11) * (65535/3.3) + // RETVAL = ADCV * s = VIN_S*1000 + // s = 1000/((65535/3.3)*(1/11)) = 0.553902494 + + // Avoid needing floating point math, so output in mV + return (adc_get(ADCCHAN_VOLTAGE) * 5539U) / 10000U; +} diff --git a/panda/board/stm32h7/llfan.h b/panda/board/stm32h7/llfan.h new file mode 100644 index 000000000..fc529dcbe --- /dev/null +++ b/panda/board/stm32h7/llfan.h @@ -0,0 +1,2 @@ +void EXTI2_IRQ_Handler(void) { } +void fan_init(void){ } diff --git a/panda/board/stm32h7/llfdcan.h b/panda/board/stm32h7/llfdcan.h new file mode 100644 index 000000000..e9440a4c4 --- /dev/null +++ b/panda/board/stm32h7/llfdcan.h @@ -0,0 +1,210 @@ +#define FDCAN_MESSAGE_RAM_SIZE 0x2800UL +#define FDCAN_START_ADDRESS 0x4000AC00UL +#define FDCAN_OFFSET 3412UL // bytes for each FDCAN module +#define FDCAN_OFFSET_W 853UL // words for each FDCAN module +#define FDCAN_END_ADDRESS 0x4000D3FCUL // Message RAM has a width of 4 Bytes + +// With this settings we can go up to 6Mbit/s +#define CAN_SYNC_JW 1U // 1 to 4 +#define CAN_PHASE_SEG1 6U // =(PROP_SEG + PHASE_SEG1) , 1 to 16 +#define CAN_PHASE_SEG2 1U // 1 to 8 +#define CAN_PCLK 48000U // Sourced from PLL1Q +#define CAN_QUANTA (1U + CAN_PHASE_SEG1 + CAN_PHASE_SEG2) +// Valid speeds in kbps and their prescalers: +// 10=600, 20=300, 50=120, 83.333=72, 100=60, 125=48, 250=24, 500=12, 1000=6, 2000=3, 3000=2, 6000=1 +#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) + +// RX FIFO 0 +#define FDCAN_RX_FIFO_0_EL_CNT 32UL +#define FDCAN_RX_FIFO_0_HEAD_SIZE 8UL // bytes +#define FDCAN_RX_FIFO_0_DATA_SIZE 8UL // 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 32UL +#define FDCAN_TX_FIFO_HEAD_SIZE 8UL // bytes +#define FDCAN_TX_FIFO_DATA_SIZE 8UL // 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)) + +// For backwards compatibility with safety code +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; + +void puts(const char *a); + +bool fdcan_request_init(FDCAN_GlobalTypeDef *CANx) { + bool ret = true; + // Exit from sleep mode + CANx->CCCR &= ~(FDCAN_CCCR_CSR); + while ((CANx->CCCR & FDCAN_CCCR_CSA) == FDCAN_CCCR_CSA); + + // Request init + uint32_t timeout_counter = 0U; + CANx->CCCR |= FDCAN_CCCR_INIT; + while ((CANx->CCCR & FDCAN_CCCR_INIT) == 0) { + // Delay for about 1ms + delay(10000); + timeout_counter++; + + if (timeout_counter >= CAN_INIT_TIMEOUT_MS){ + ret = false; + break; + } + } + return ret; +} + +bool fdcan_exit_init(FDCAN_GlobalTypeDef *CANx) { + bool ret = true; + + CANx->CCCR &= ~(FDCAN_CCCR_INIT); + uint32_t timeout_counter = 0U; + while ((CANx->CCCR & FDCAN_CCCR_INIT) != 0) { + // Delay for about 1ms + delay(10000); + timeout_counter++; + + if (timeout_counter >= CAN_INIT_TIMEOUT_MS) { + ret = false; + break; + } + } + return ret; +} + +bool llcan_set_speed(FDCAN_GlobalTypeDef *CANx, uint32_t speed, uint32_t data_speed, bool loopback, bool silent) { + bool ret = fdcan_request_init(CANx); + + if (ret) { + // Enable config change + CANx->CCCR |= FDCAN_CCCR_CCE; + + //Reset operation mode to Normal + CANx->CCCR &= ~(FDCAN_CCCR_TEST); + CANx->TEST &= ~(FDCAN_TEST_LBCK); + CANx->CCCR &= ~(FDCAN_CCCR_MON); + CANx->CCCR &= ~(FDCAN_CCCR_ASM); + + // Set the nominal bit timing register + CANx->NBTP = ((CAN_SYNC_JW-1U)<DBTP = ((CAN_SYNC_JW-1U)<CCCR |= FDCAN_CCCR_TEST; + CANx->TEST |= FDCAN_TEST_LBCK; + CANx->CCCR |= FDCAN_CCCR_MON; + } + // Silent is known as bus monitoring in the docs + if (silent) { + CANx->CCCR |= FDCAN_CCCR_MON; + } + ret = fdcan_exit_init(CANx); + if (!ret) { + puts(CAN_NAME_FROM_CANIF(CANx)); puts(" set_speed timed out! (2)\n"); + } + } else { + puts(CAN_NAME_FROM_CANIF(CANx)); puts(" set_speed timed out! (1)\n"); + } + return ret; +} + +bool llcan_init(FDCAN_GlobalTypeDef *CANx) { + uint32_t can_number = CAN_NUM_FROM_CANIF(CANx); + bool ret = fdcan_request_init(CANx); + + if (ret) { + // Enable config change + CANx->CCCR |= FDCAN_CCCR_CCE; + // Enable automatic retransmission + CANx->CCCR &= ~(FDCAN_CCCR_DAR); + // Enable transmission pause feature + CANx->CCCR |= FDCAN_CCCR_TXP; + // Disable protocol exception handling + CANx->CCCR |= FDCAN_CCCR_PXHD; + // FD with BRS + CANx->CCCR |= (FDCAN_CCCR_FDOE | FDCAN_CCCR_BRSE); + + // Set TX mode to FIFO + CANx->TXBC &= ~(FDCAN_TXBC_TFQM); + // Configure TX element size (for now 8 bytes, no need to change) + //CANx->TXESC |= 0x000U; + //Configure RX FIFO0, FIFO1, RX buffer element sizes (no need for now, using classic 8 bytes) + register_set(&(CANx->RXESC), 0x0U, (FDCAN_RXESC_F0DS | FDCAN_RXESC_F1DS | FDCAN_RXESC_RBDS)); + // Disable filtering, accept all valid frames received + CANx->XIDFC &= ~(FDCAN_XIDFC_LSE); // No extended filters + CANx->SIDFC &= ~(FDCAN_SIDFC_LSS); // No standard filters + CANx->GFC &= ~(FDCAN_GFC_RRFE); // Accept extended remote frames + CANx->GFC &= ~(FDCAN_GFC_RRFS); // Accept standard remote frames + CANx->GFC &= ~(FDCAN_GFC_ANFE); // Accept extended frames to FIFO 0 + CANx->GFC &= ~(FDCAN_GFC_ANFS); // Accept standard frames to FIFO 0 + + uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET); + uint32_t TxFIFOSA = RxFIFO0SA + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); + + // RX FIFO 0 + CANx->RXF0C = (FDCAN_RX_FIFO_0_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_RXF0C_F0SA_Pos; + CANx->RXF0C |= FDCAN_RX_FIFO_0_EL_CNT << FDCAN_RXF0C_F0S_Pos; + // RX FIFO 0 switch to non-blocking (overwrite) mode + CANx->RXF0C |= FDCAN_RXF0C_F0OM; + + // TX FIFO (mode set earlier) + CANx->TXBC = (FDCAN_TX_FIFO_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_TXBC_TBSA_Pos; + CANx->TXBC |= FDCAN_TX_FIFO_EL_CNT << FDCAN_TXBC_TFQS_Pos; + + // Flush allocated RAM + uint32_t EndAddress = TxFIFOSA + (FDCAN_TX_FIFO_EL_CNT * FDCAN_TX_FIFO_EL_SIZE); + for (uint32_t RAMcounter = RxFIFO0SA; RAMcounter < EndAddress; RAMcounter += 4U) { + *(uint32_t *)(RAMcounter) = 0x00000000; + } + + // Enable both interrupts for each module + CANx->ILE = (FDCAN_ILE_EINT0 | FDCAN_ILE_EINT1); + + CANx->IE &= 0x0U; // Reset all interrupts + // Messages for INT0 + CANx->IE |= FDCAN_IE_RF0NE; // Rx FIFO 0 new message + + // Messages for INT1 (Only TFE works??) + CANx->ILS |= FDCAN_ILS_TFEL; + CANx->IE |= FDCAN_IE_TFEE; // Tx FIFO empty + + ret = fdcan_exit_init(CANx); + if(!ret) { + puts(CAN_NAME_FROM_CANIF(CANx)); puts(" llcan_init timed out (2)!\n"); + } + + if (CANx == FDCAN1) { + NVIC_EnableIRQ(FDCAN1_IT0_IRQn); + NVIC_EnableIRQ(FDCAN1_IT1_IRQn); + } else if (CANx == FDCAN2) { + NVIC_EnableIRQ(FDCAN2_IT0_IRQn); + NVIC_EnableIRQ(FDCAN2_IT1_IRQn); + } else if (CANx == FDCAN3) { + NVIC_EnableIRQ(FDCAN3_IT0_IRQn); + NVIC_EnableIRQ(FDCAN3_IT1_IRQn); + } else { + puts("Invalid CAN: initialization failed\n"); + } + + } else { + puts(CAN_NAME_FROM_CANIF(CANx)); puts(" llcan_init timed out (1)!\n"); + } + return ret; +} + +void llcan_clear_send(FDCAN_GlobalTypeDef *CANx) { + // From H7 datasheet: Transmit cancellation is not intended for Tx FIFO operation. + UNUSED(CANx); +} diff --git a/panda/board/stm32h7/llflash.h b/panda/board/stm32h7/llflash.h new file mode 100644 index 000000000..b95011a9e --- /dev/null +++ b/panda/board/stm32h7/llflash.h @@ -0,0 +1,33 @@ +bool flash_is_locked(void) { + return (FLASH->CR1 & FLASH_CR_LOCK); +} + +void flash_unlock(void) { + FLASH->KEYR1 = 0x45670123; + FLASH->KEYR1 = 0xCDEF89AB; +} + +bool flash_erase_sector(uint8_t sector, bool unlocked) { + // don't erase the bootloader(sector 0) + if (sector != 0 && sector < 8 && unlocked) { + FLASH->CR1 = (sector << 8) | FLASH_CR_SER; + FLASH->CR1 |= FLASH_CR_START; + while (FLASH->SR1 & FLASH_SR_QW); + return true; + } + return false; +} + +void flash_write_word(void *prog_ptr, uint32_t data) { + uint32_t *pp = prog_ptr; + FLASH->CR1 |= FLASH_CR_PG; + *pp = data; + while (FLASH->SR1 & FLASH_SR_QW); +} + +void flush_write_buffer(void) { + if (FLASH->SR1 & FLASH_SR_WBNE) { + FLASH->CR1 |= FLASH_CR_FW; + while (FLASH->SR1 & FLASH_CR_FW); + } +} diff --git a/panda/board/stm32h7/llrtc.h b/panda/board/stm32h7/llrtc.h new file mode 100644 index 000000000..8689f8952 --- /dev/null +++ b/panda/board/stm32h7/llrtc.h @@ -0,0 +1,9 @@ +#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEDRV | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) + +void enable_bdomain_protection(void) { + register_clear_bits(&(PWR->CR1), PWR_CR1_DBP); +} + +void disable_bdomain_protection(void) { + register_set_bits(&(PWR->CR1), PWR_CR1_DBP); +} diff --git a/panda/board/stm32h7/lluart.h b/panda/board/stm32h7/lluart.h new file mode 100644 index 000000000..aa44f7bb8 --- /dev/null +++ b/panda/board/stm32h7/lluart.h @@ -0,0 +1,5 @@ +void uart_init(uart_ring *q, int baud) { UNUSED(q); UNUSED(baud); } +void uart_set_baud(USART_TypeDef *u, unsigned int baud) { UNUSED(u); UNUSED(baud); } +void dma_pointer_handler(uart_ring *q, uint32_t dma_ndtr) { UNUSED(q); UNUSED(dma_ndtr); } +void uart_rx_ring(uart_ring *q) { UNUSED(q); } +void uart_tx_ring(uart_ring *q) { UNUSED(q); } diff --git a/panda/board/stm32h7/llusb.h b/panda/board/stm32h7/llusb.h new file mode 100644 index 000000000..58646574a --- /dev/null +++ b/panda/board/stm32h7/llusb.h @@ -0,0 +1,98 @@ +typedef struct +{ + __IO uint32_t HPRT; +} +USB_OTG_HostPortTypeDef; + +USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; + +#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) +#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) +#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) +#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) +#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) +#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) +#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) + +#define USBD_FS_TRDT_VALUE 6U +#define USB_OTG_SPEED_FULL 3U +#define DCFG_FRAME_INTERVAL_80 0U + + +void usb_irqhandler(void); + +void OTG_HS_IRQ_Handler(void) { + NVIC_DisableIRQ(OTG_HS_IRQn); + usb_irqhandler(); + NVIC_EnableIRQ(OTG_HS_IRQn); +} + +void usb_init(void) { + REGISTER_INTERRUPT(OTG_HS_IRQn, OTG_HS_IRQ_Handler, 1500000U, FAULT_INTERRUPT_RATE_USB) // TODO: Find out a better rate limit for USB. Now it's the 1.5MB/s rate + + // Disable global interrupt + USBx->GAHBCFG &= ~(USB_OTG_GAHBCFG_GINT); + // Select FS Embedded PHY + USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + // Force device mode + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); + USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + delay(250000); // Wait for about 25ms (explicitly stated in H7 ref manual) + // Wait for AHB master IDLE state. + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); + // Core Soft Reset + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + // Activate the USB Transceiver + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + + for (uint8_t i = 0U; i < 15U; i++) { + USBx->DIEPTXF[i] = 0U; + } + + // VBUS Sensing setup + 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; + // Restart the Phy Clock + USBx_PCGCCTL = 0U; + // Device mode configuration + USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; + USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; + + // Flush FIFOs + USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (0x10U << 6)); + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + // Clear all pending Device Interrupts + USBx_DEVICE->DIEPMSK = 0U; + USBx_DEVICE->DOEPMSK = 0U; + USBx_DEVICE->DAINTMSK = 0U; + USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); + + // Disable all interrupts. + USBx->GINTMSK = 0U; + // Clear any pending interrupts + USBx->GINTSTS = 0xBFFFFFFFU; + // Enable interrupts matching to the Device mode ONLY + USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | + USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | + USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_USBSUSPM | + USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM | USB_OTG_GINTMSK_EOPFM; + + // Set USB Turnaround time + USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); + // Enables the controller's Global Int in the AHB Config reg + USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + // Soft disconnect disable: + USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_SDIS); + + // enable the IRQ + NVIC_EnableIRQ(OTG_HS_IRQn); +} diff --git a/panda/board/stm32h7/peripherals.h b/panda/board/stm32h7/peripherals.h new file mode 100644 index 000000000..b50516f79 --- /dev/null +++ b/panda/board/stm32h7/peripherals.h @@ -0,0 +1,123 @@ +void gpio_usb_init(void) { + // A11,A12: USB: + set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG1_FS); + set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG1_FS); + GPIOA->OSPEEDR = GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12; +} + +void gpio_usart2_init(void) { + // A2,A3: USART 2 for debugging + set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); + set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); +} + +// Common GPIO initialization +void common_init_gpio(void) { + /// E2,E3,E4: RGB LED + set_gpio_pullup(GPIOE, 2, PULL_NONE); + set_gpio_mode(GPIOE, 2, MODE_OUTPUT); + + set_gpio_pullup(GPIOE, 3, PULL_NONE); + set_gpio_mode(GPIOE, 3, MODE_OUTPUT); + + set_gpio_pullup(GPIOE, 4, PULL_NONE); + set_gpio_mode(GPIOE, 4, MODE_OUTPUT); + + // F7,F8,F9,F10: BOARD ID + set_gpio_pullup(GPIOF, 7, PULL_NONE); + set_gpio_mode(GPIOF, 7, MODE_INPUT); + + set_gpio_pullup(GPIOF, 8, PULL_NONE); + set_gpio_mode(GPIOF, 8, MODE_INPUT); + + set_gpio_pullup(GPIOF, 9, PULL_NONE); + set_gpio_mode(GPIOF, 9, MODE_INPUT); + + set_gpio_pullup(GPIOF, 10, PULL_NONE); + set_gpio_mode(GPIOF, 10, MODE_INPUT); + + // G11,B3,D7,B4: transceiver enable + set_gpio_pullup(GPIOG, 11, PULL_NONE); + set_gpio_mode(GPIOG, 11, MODE_OUTPUT); + + // Speed was set to high by default after reset, changing to low + GPIOB->OSPEEDR = GPIO_OSPEEDR_OSPEED3; + set_gpio_pullup(GPIOB, 3, PULL_NONE); + set_gpio_mode(GPIOB, 3, MODE_OUTPUT); + + set_gpio_pullup(GPIOD, 7, PULL_NONE); + set_gpio_mode(GPIOD, 7, MODE_OUTPUT); + + set_gpio_pullup(GPIOB, 4, PULL_NONE); + set_gpio_mode(GPIOB, 4, MODE_OUTPUT); + + // B14: usb load switch + set_gpio_pullup(GPIOB, 14, PULL_NONE); + set_gpio_mode(GPIOB, 14, MODE_OUTPUT); + + //B1,F11 5VOUT_S, VOLT_S + set_gpio_pullup(GPIOB, 1, PULL_NONE); + set_gpio_mode(GPIOB, 1, MODE_ANALOG); + + set_gpio_pullup(GPIOF, 11, PULL_NONE); + set_gpio_mode(GPIOF, 11, MODE_ANALOG); + + gpio_usb_init(); + + // B8,B9: FDCAN1 + set_gpio_pullup(GPIOB, 8, PULL_NONE); + set_gpio_alternate(GPIOB, 8, GPIO_AF9_FDCAN1); + + set_gpio_pullup(GPIOB, 9, PULL_NONE); + set_gpio_alternate(GPIOB, 9, GPIO_AF9_FDCAN1); + + // B5,B6 (mplex to B12,B13): FDCAN2 + set_gpio_pullup(GPIOB, 12, PULL_NONE); + set_gpio_pullup(GPIOB, 13, PULL_NONE); + + set_gpio_pullup(GPIOB, 5, PULL_NONE); + set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); + + set_gpio_pullup(GPIOB, 6, PULL_NONE); + set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); + + // G9,G10: FDCAN3 + set_gpio_pullup(GPIOG, 9, PULL_NONE); + set_gpio_alternate(GPIOG, 9, GPIO_AF2_FDCAN3); + + set_gpio_pullup(GPIOG, 10, PULL_NONE); + set_gpio_alternate(GPIOG, 10, GPIO_AF2_FDCAN3); +} + +void flasher_peripherals_init(void) { + RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; +} + +// Peripheral initialization +void peripherals_init(void) { + // enable GPIO(A,B,C,D,E,F,G,H) + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOAEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOBEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOCEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIODEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOEEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOFEN; + RCC->AHB4ENR |= RCC_AHB4ENR_GPIOGEN; + + RCC->APB1LENR |= RCC_APB1LENR_TIM2EN; // main counter + RCC->APB1LENR |= RCC_APB1LENR_TIM6EN; // interrupt timer + RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; // clock source timer + RCC->APB1LENR |= RCC_APB1LENR_TIM12EN; // slow loop + + RCC->APB1HENR |= RCC_APB1HENR_FDCANEN; // FDCAN core enable + RCC->AHB1ENR |= RCC_AHB1ENR_ADC12EN; // Enable ADC clocks + + // HS USB enable, also LP is needed for CSleep state(__WFI()) + RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; + RCC->AHB1LPENR |= RCC_AHB1LPENR_USB1OTGHSLPEN; + RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_USB1OTGHSULPILPEN); +} + +void enable_interrupt_timer(void) { + register_set_bits(&(RCC->APB1LENR), RCC_APB1LENR_TIM6EN); // Enable interrupt timer peripheral +} diff --git a/panda/board/stm32h7/startup_stm32h7x5xx.s b/panda/board/stm32h7/startup_stm32h7x5xx.s new file mode 100644 index 000000000..15015a113 --- /dev/null +++ b/panda/board/stm32h7/startup_stm32h7x5xx.s @@ -0,0 +1,767 @@ +/** + ****************************************************************************** + * @file startup_stm32h735xx.s + * @author MCD Application Team + * @brief STM32H735xx Devices vector table for GCC based toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @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 + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m7 + .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 */ + ldr r0, =_sdata + ldr r1, =_edata + ldr r2, =_sidata + movs r3, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r4, [r2, r3] + str r4, [r0, r3] + adds r3, r3, #4 + +LoopCopyDataInit: + adds r4, r0, r3 + cmp r4, r1 + bcc CopyDataInit +/* Zero fill the bss segment. */ + ldr r2, =_sbss + ldr r4, =_ebss + movs r3, #0 + b LoopFillZerobss + +FillZerobss: + str r3, [r2] + adds r2, r2, #4 + +LoopFillZerobss: + cmp r2, r4 + 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 M. 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_AVD_IRQHandler /* PVD/AVD 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 FDCAN1_IT0_IRQHandler /* FDCAN1 interrupt line 0 */ + .word FDCAN2_IT0_IRQHandler /* FDCAN2 interrupt line 0 */ + .word FDCAN1_IT1_IRQHandler /* FDCAN1 interrupt line 1 */ + .word FDCAN2_IT1_IRQHandler /* FDCAN2 interrupt line 1 */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_IRQHandler /* TIM1 Break interrupt */ + .word TIM1_UP_IRQHandler /* TIM1 Update interrupt */ + .word TIM1_TRG_COM_IRQHandler /* TIM1 Trigger and Commutation interrupt */ + .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 0 /* Reserved */ + .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 FMC_IRQHandler /* FMC */ + .word SDMMC1_IRQHandler /* SDMMC1 */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word ETH_IRQHandler /* Ethernet */ + .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ + .word FDCAN_CAL_IRQHandler /* FDCAN calibration unit interrupt*/ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word DCMI_PSSI_IRQHandler /* DCMI, PSSI */ + .word CRYP_IRQHandler /* CRYP */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ + .word SPI6_IRQHandler /* SPI6 */ + .word SAI1_IRQHandler /* SAI1 */ + .word LTDC_IRQHandler /* LTDC */ + .word LTDC_ER_IRQHandler /* LTDC error */ + .word DMA2D_IRQHandler /* DMA2D */ + .word 0 /* Reserved */ + .word OCTOSPI1_IRQHandler /* OCTOSPI1 */ + .word LPTIM1_IRQHandler /* LPTIM1 */ + .word CEC_IRQHandler /* HDMI_CEC */ + .word I2C4_EV_IRQHandler /* I2C4 Event */ + .word I2C4_ER_IRQHandler /* I2C4 Error */ + .word SPDIF_RX_IRQHandler /* SPDIF_RX */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DFSDM1_FLT0_IRQHandler /* DFSDM Filter0 Interrupt */ + .word DFSDM1_FLT1_IRQHandler /* DFSDM Filter1 Interrupt */ + .word DFSDM1_FLT2_IRQHandler /* DFSDM Filter2 Interrupt */ + .word DFSDM1_FLT3_IRQHandler /* DFSDM Filter3 Interrupt */ + .word 0 /* Reserved */ + .word SWPMI1_IRQHandler /* Serial Wire Interface 1 global interrupt */ + .word TIM15_IRQHandler /* TIM15 global Interrupt */ + .word TIM16_IRQHandler /* TIM16 global Interrupt */ + .word TIM17_IRQHandler /* TIM17 global Interrupt */ + .word MDIOS_WKUP_IRQHandler /* MDIOS Wakeup Interrupt */ + .word MDIOS_IRQHandler /* MDIOS global Interrupt */ + .word 0 /* Reserved */ + .word MDMA_IRQHandler /* MDMA global Interrupt */ + .word 0 /* Reserved */ + .word SDMMC2_IRQHandler /* SDMMC2 global Interrupt */ + .word HSEM1_IRQHandler /* HSEM1 global Interrupt */ + .word 0 /* Reserved */ + .word ADC3_IRQHandler /* ADC3 global Interrupt */ + .word DMAMUX2_OVR_IRQHandler /* DMAMUX Overrun interrupt */ + .word BDMA_Channel0_IRQHandler /* BDMA Channel 0 global Interrupt */ + .word BDMA_Channel1_IRQHandler /* BDMA Channel 1 global Interrupt */ + .word BDMA_Channel2_IRQHandler /* BDMA Channel 2 global Interrupt */ + .word BDMA_Channel3_IRQHandler /* BDMA Channel 3 global Interrupt */ + .word BDMA_Channel4_IRQHandler /* BDMA Channel 4 global Interrupt */ + .word BDMA_Channel5_IRQHandler /* BDMA Channel 5 global Interrupt */ + .word BDMA_Channel6_IRQHandler /* BDMA Channel 6 global Interrupt */ + .word BDMA_Channel7_IRQHandler /* BDMA Channel 7 global Interrupt */ + .word COMP1_IRQHandler /* COMP1 global Interrupt */ + .word LPTIM2_IRQHandler /* LP TIM2 global interrupt */ + .word LPTIM3_IRQHandler /* LP TIM3 global interrupt */ + .word LPTIM4_IRQHandler /* LP TIM4 global interrupt */ + .word LPTIM5_IRQHandler /* LP TIM5 global interrupt */ + .word LPUART1_IRQHandler /* LP UART1 interrupt */ + .word 0 /* Reserved */ + .word CRS_IRQHandler /* Clock Recovery Global Interrupt */ + .word ECC_IRQHandler /* ECC diagnostic Global Interrupt */ + .word SAI4_IRQHandler /* SAI4 global interrupt */ + .word DTS_IRQHandler /* Digital Temperature Sensor interrupt */ + .word 0 /* Reserved */ + .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */ + .word OCTOSPI2_IRQHandler /* OCTOSPI2 Interrupt */ + .word OTFDEC1_IRQHandler /* OTFDEC1 Interrupt */ + .word OTFDEC2_IRQHandler /* OTFDEC2 Interrupt */ + .word FMAC_IRQHandler /* FMAC Interrupt */ + .word CORDIC_IRQHandler /* CORDIC Interrupt */ + .word UART9_IRQHandler /* UART9 Interrupt */ + .word USART10_IRQHandler /* UART10 Interrupt */ + .word I2C5_EV_IRQHandler /* I2C5 Event Interrupt */ + .word I2C5_ER_IRQHandler /* I2C5 Error Interrupt */ + .word FDCAN3_IT0_IRQHandler /* FDCAN3 interrupt line 0 */ + .word FDCAN3_IT1_IRQHandler /* FDCAN3 interrupt line 1 */ + .word TIM23_IRQHandler /* TIM23 global interrupt */ + .word TIM24_IRQHandler /* TIM24 global interrupt */ + +/******************************************************************************* +* +* 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_AVD_IRQHandler + .thumb_set PVD_AVD_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 FDCAN1_IT0_IRQHandler + .thumb_set FDCAN1_IT0_IRQHandler,Default_Handler + + .weak FDCAN2_IT0_IRQHandler + .thumb_set FDCAN2_IT0_IRQHandler,Default_Handler + + .weak FDCAN1_IT1_IRQHandler + .thumb_set FDCAN1_IT1_IRQHandler,Default_Handler + + .weak FDCAN2_IT1_IRQHandler + .thumb_set FDCAN2_IT1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_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 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 FMC_IRQHandler + .thumb_set FMC_IRQHandler,Default_Handler + + .weak SDMMC1_IRQHandler + .thumb_set SDMMC1_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 ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak FDCAN_CAL_IRQHandler + .thumb_set FDCAN_CAL_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak DCMI_PSSI_IRQHandler + .thumb_set DCMI_PSSI_IRQHandler,Default_Handler + + .weak CRYP_IRQHandler + .thumb_set CRYP_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_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 SPI6_IRQHandler + .thumb_set SPI6_IRQHandler,Default_Handler + + .weak SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak LTDC_IRQHandler + .thumb_set LTDC_IRQHandler,Default_Handler + + .weak LTDC_ER_IRQHandler + .thumb_set LTDC_ER_IRQHandler,Default_Handler + + .weak DMA2D_IRQHandler + .thumb_set DMA2D_IRQHandler,Default_Handler + + .weak OCTOSPI1_IRQHandler + .thumb_set OCTOSPI1_IRQHandler,Default_Handler + + .weak LPTIM1_IRQHandler + .thumb_set LPTIM1_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak I2C4_EV_IRQHandler + .thumb_set I2C4_EV_IRQHandler,Default_Handler + + .weak I2C4_ER_IRQHandler + .thumb_set I2C4_ER_IRQHandler,Default_Handler + + .weak SPDIF_RX_IRQHandler + .thumb_set SPDIF_RX_IRQHandler,Default_Handler + + .weak DMAMUX1_OVR_IRQHandler + .thumb_set DMAMUX1_OVR_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 DFSDM1_FLT2_IRQHandler + .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler + + .weak DFSDM1_FLT3_IRQHandler + .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler + + .weak SWPMI1_IRQHandler + .thumb_set SWPMI1_IRQHandler,Default_Handler + + .weak TIM15_IRQHandler + .thumb_set TIM15_IRQHandler,Default_Handler + + .weak TIM16_IRQHandler + .thumb_set TIM16_IRQHandler,Default_Handler + + .weak TIM17_IRQHandler + .thumb_set TIM17_IRQHandler,Default_Handler + + .weak MDIOS_WKUP_IRQHandler + .thumb_set MDIOS_WKUP_IRQHandler,Default_Handler + + .weak MDIOS_IRQHandler + .thumb_set MDIOS_IRQHandler,Default_Handler + + .weak MDMA_IRQHandler + .thumb_set MDMA_IRQHandler,Default_Handler + + .weak SDMMC2_IRQHandler + .thumb_set SDMMC2_IRQHandler,Default_Handler + + .weak HSEM1_IRQHandler + .thumb_set HSEM1_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak DMAMUX2_OVR_IRQHandler + .thumb_set DMAMUX2_OVR_IRQHandler,Default_Handler + + .weak BDMA_Channel0_IRQHandler + .thumb_set BDMA_Channel0_IRQHandler,Default_Handler + + .weak BDMA_Channel1_IRQHandler + .thumb_set BDMA_Channel1_IRQHandler,Default_Handler + + .weak BDMA_Channel2_IRQHandler + .thumb_set BDMA_Channel2_IRQHandler,Default_Handler + + .weak BDMA_Channel3_IRQHandler + .thumb_set BDMA_Channel3_IRQHandler,Default_Handler + + .weak BDMA_Channel4_IRQHandler + .thumb_set BDMA_Channel4_IRQHandler,Default_Handler + + .weak BDMA_Channel5_IRQHandler + .thumb_set BDMA_Channel5_IRQHandler,Default_Handler + + .weak BDMA_Channel6_IRQHandler + .thumb_set BDMA_Channel6_IRQHandler,Default_Handler + + .weak BDMA_Channel7_IRQHandler + .thumb_set BDMA_Channel7_IRQHandler,Default_Handler + + .weak COMP1_IRQHandler + .thumb_set COMP1_IRQHandler,Default_Handler + + .weak LPTIM2_IRQHandler + .thumb_set LPTIM2_IRQHandler,Default_Handler + + .weak LPTIM3_IRQHandler + .thumb_set LPTIM3_IRQHandler,Default_Handler + + .weak LPTIM4_IRQHandler + .thumb_set LPTIM4_IRQHandler,Default_Handler + + .weak LPTIM5_IRQHandler + .thumb_set LPTIM5_IRQHandler,Default_Handler + + .weak LPUART1_IRQHandler + .thumb_set LPUART1_IRQHandler,Default_Handler + + .weak CRS_IRQHandler + .thumb_set CRS_IRQHandler,Default_Handler + + .weak ECC_IRQHandler + .thumb_set ECC_IRQHandler,Default_Handler + + .weak SAI4_IRQHandler + .thumb_set SAI4_IRQHandler,Default_Handler + + .weak DTS_IRQHandler + .thumb_set DTS_IRQHandler,Default_Handler + + .weak WAKEUP_PIN_IRQHandler + .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler + + .weak OCTOSPI2_IRQHandler + .thumb_set OCTOSPI2_IRQHandler,Default_Handler + + .weak OTFDEC1_IRQHandler + .thumb_set OTFDEC1_IRQHandler,Default_Handler + + .weak OTFDEC2_IRQHandler + .thumb_set OTFDEC2_IRQHandler,Default_Handler + + .weak FMAC_IRQHandler + .thumb_set FMAC_IRQHandler,Default_Handler + + .weak CORDIC_IRQHandler + .thumb_set CORDIC_IRQHandler,Default_Handler + + .weak UART9_IRQHandler + .thumb_set UART9_IRQHandler,Default_Handler + + .weak USART10_IRQHandler + .thumb_set USART10_IRQHandler,Default_Handler + + .weak I2C5_EV_IRQHandler + .thumb_set I2C5_EV_IRQHandler,Default_Handler + + .weak I2C5_ER_IRQHandler + .thumb_set I2C5_ER_IRQHandler,Default_Handler + + .weak FDCAN3_IT0_IRQHandler + .thumb_set FDCAN3_IT0_IRQHandler,Default_Handler + + .weak FDCAN3_IT1_IRQHandler + .thumb_set FDCAN3_IT1_IRQHandler,Default_Handler + + .weak TIM23_IRQHandler + .thumb_set TIM23_IRQHandler,Default_Handler + + .weak TIM24_IRQHandler + .thumb_set TIM24_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h new file mode 100644 index 000000000..a295d18ab --- /dev/null +++ b/panda/board/stm32h7/stm32h7_config.h @@ -0,0 +1,75 @@ +#include "stm32h7/inc/stm32h7xx.h" +#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/2U +#define APB2_FREQ CORE_FREQ/2U + +#define BOOTLOADER_ADDRESS 0x1FF09804U + +// Around (1Mbps / 8 bits/byte / 12 bytes per message) +#define CAN_INTERRUPT_RATE 12000U // FIXME: should raise to 16000 ? + +#define MAX_LED_FADE 10240U + +// Threshold voltage (mV) for either of the SBUs to be below before deciding harness is connected +#define HARNESS_CONNECTED_THRESHOLD 40000U + +// There are 163 external interrupt sources (see stm32f735xx.h) +#define NUM_INTERRUPTS 163U + +#define TICK_TIMER_IRQ TIM8_BRK_TIM12_IRQn +#define TICK_TIMER TIM12 + +#define MICROSECOND_TIMER TIM2 + +#define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn +#define INTERRUPT_TIMER TIM6 + +#define PROVISION_CHUNK_ADDRESS 0x080FFFE0U +#define DEVICE_SERIAL_NUMBER_ADDRESS 0x080FFFC0U + +#ifndef BOOTSTUB + #include "main_declarations.h" +#else + #include "bootstub_declarations.h" +#endif + +#include "libc.h" +#include "critical.h" +#include "faults.h" + +#include "drivers/registers.h" +#include "drivers/interrupts.h" +#include "drivers/gpio.h" +#include "stm32h7/peripherals.h" +#include "stm32h7/interrupt_handlers.h" +#include "drivers/timers.h" +#include "stm32h7/lladc.h" +#include "stm32h7/board.h" +#include "stm32h7/clock.h" + +#if !defined (BOOTSTUB) && defined(PANDA) + #include "drivers/uart.h" + #include "stm32h7/lluart.h" +#endif + +#ifdef BOOTSTUB + #include "stm32h7/llflash.h" +#else + #include "stm32h7/llfdcan.h" +#endif + +#include "stm32h7/llusb.h" + +void early_gpio_float(void) { + RCC->AHB4ENR = RCC_AHB4ENR_GPIOAEN | RCC_AHB4ENR_GPIOBEN | RCC_AHB4ENR_GPIOCEN | RCC_AHB4ENR_GPIODEN | RCC_AHB4ENR_GPIOEEN | RCC_AHB4ENR_GPIOFEN | RCC_AHB4ENR_GPIOGEN | RCC_AHB4ENR_GPIOHEN; + GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0; GPIOD->MODER = 0; GPIOE->MODER = 0; GPIOF->MODER = 0; GPIOG->MODER = 0; GPIOH->MODER = 0; + GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; GPIOD->ODR = 0; GPIOE->ODR = 0; GPIOF->ODR = 0; GPIOG->ODR = 0; GPIOH->ODR = 0; + GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; GPIOD->PUPDR = 0; GPIOE->PUPDR = 0; GPIOF->PUPDR = 0; GPIOG->PUPDR = 0; GPIOH->PUPDR = 0; +} diff --git a/panda/board/stm32h7/stm32h7x5_flash.ld b/panda/board/stm32h7/stm32h7x5_flash.ld new file mode 100644 index 000000000..f03600b5e --- /dev/null +++ b/panda/board/stm32h7/stm32h7x5_flash.ld @@ -0,0 +1,186 @@ +/* +****************************************************************************** +** + +** File : LinkerScript.ld +** +** Author : Auto-generated by System Workbench for STM32 +** +** Abstract : Linker script for STM32H735ZGTx series +** 1024Kbytes FLASH and 560Kbytes 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. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2019 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. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +enter_bootloader_mode = 0x38001FFC; +_estack = 0x20020000; /* end of RAM */ +_app_start = 0x08020000; /* Reserve Sector 0(128K) 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 +{ +DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 320K +RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K +RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K +ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K +} + +/* 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 */ + } >DTCMRAM 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; + } >DTCMRAM + + /* 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); + } >DTCMRAM + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/panda/python/__init__.py b/panda/python/__init__.py index a4b0dbba0..5d0d15186 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -8,17 +8,16 @@ import os import time import traceback import sys -from .dfu import PandaDFU # pylint: disable=import-error +from .dfu import PandaDFU, MCU_TYPE_F2, MCU_TYPE_F4, MCU_TYPE_H7 # pylint: disable=import-error from .flash_release import flash_release # noqa pylint: disable=import-error from .update import ensure_st_up_to_date # noqa pylint: disable=import-error from .serial import PandaSerial # noqa pylint: disable=import-error from .isotp import isotp_send, isotp_recv # pylint: disable=import-error - +from .config import DEFAULT_FW_FN, DEFAULT_H7_FW_FN # noqa pylint: disable=import-error __version__ = '0.0.9' BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") -DEFAULT_FW_FN = os.path.join(BASEDIR, "board", "obj", "panda.bin.signed") DEBUG = os.getenv("PANDADEBUG") is not None @@ -139,6 +138,11 @@ class Panda(object): HW_TYPE_PEDAL = b'\x04' HW_TYPE_UNO = b'\x05' HW_TYPE_DOS = b'\x06' + HW_TYPE_RED_PANDA = b'\x07' + + F2_DEVICES = [HW_TYPE_PEDAL] + F4_DEVICES = [HW_TYPE_WHITE_PANDA, HW_TYPE_GREY_PANDA, HW_TYPE_BLACK_PANDA, HW_TYPE_UNO, HW_TYPE_DOS] + H7_DEVICES = [HW_TYPE_RED_PANDA] CLOCK_SOURCE_MODE_DISABLED = 0 CLOCK_SOURCE_MODE_FREE_RUNNING = 1 @@ -151,6 +155,7 @@ class Panda(object): self._serial = serial self._handle = None self.connect(claim) + self._mcu_type = self.get_mcu_type() def close(self): self._handle.close() @@ -225,7 +230,7 @@ class Panda(object): except Exception: print("reconnecting is taking %d seconds..." % (i + 1)) try: - dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial, self._mcu_type)) dfu.recover() except Exception: pass @@ -262,6 +267,8 @@ class Panda(object): pass def flash(self, fn=DEFAULT_FW_FN, code=None, reconnect=True): + if self._mcu_type == MCU_TYPE_H7 and fn == DEFAULT_FW_FN: + fn = DEFAULT_H7_FW_FN print("flash: main version is " + self.get_version()) if not self.bootstub: self.reset(enter_bootstub=True) @@ -291,7 +298,7 @@ class Panda(object): if timeout is not None and (time.time() - t_start) > timeout: return False - dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial, self._mcu_type)) dfu.recover() # reflash after recover @@ -401,9 +408,25 @@ class Panda(object): def is_dos(self): return self.get_type() == Panda.HW_TYPE_DOS + + def is_red(self): + return self.get_type() == Panda.HW_TYPE_RED_PANDA + + def get_mcu_type(self): + hw_type = self.get_type() + if hw_type in Panda.F2_DEVICES: + return MCU_TYPE_F2 + elif hw_type in Panda.F4_DEVICES: + return MCU_TYPE_F4 + elif hw_type in Panda.H7_DEVICES: + return MCU_TYPE_H7 + return None def has_obd(self): - return (self.is_uno() or self.is_dos() or self.is_black()) + return (self.is_uno() or self.is_dos() or self.is_black() or self.is_red()) + + def has_canfd(self): + return self._mcu_type in Panda.H7_DEVICES def get_serial(self): dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20) @@ -460,6 +483,9 @@ class Panda(object): def set_can_speed_kbps(self, bus, speed): self._handle.controlWrite(Panda.REQUEST_OUT, 0xde, bus, int(speed * 10), b'') + def set_can_data_speed_kbps(self, bus, speed): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf9, bus, int(speed * 10), b'') + def set_uart_baud(self, uart, rate): self._handle.controlWrite(Panda.REQUEST_OUT, 0xe4, uart, int(rate / 300), b'') diff --git a/panda/python/config.py b/panda/python/config.py new file mode 100644 index 000000000..9b890a131 --- /dev/null +++ b/panda/python/config.py @@ -0,0 +1,18 @@ +import os + + +BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") + +BOOTSTUB_ADDRESS = 0x8000000 + +BLOCK_SIZE_FX = 0x800 +APP_ADDRESS_FX = 0x8004000 +DEVICE_SERIAL_NUMBER_ADDR_FX = 0x1FFF79C0 +DEFAULT_FW_FN = os.path.join(BASEDIR, "board", "obj", "panda.bin.signed") +DEFAULT_BOOTSTUB_FN = os.path.join(BASEDIR, "board", "obj", "bootstub.panda.bin") + +BLOCK_SIZE_H7 = 0x400 +APP_ADDRESS_H7 = 0x8020000 +DEVICE_SERIAL_NUMBER_ADDR_H7 = 0x080FFFC0 +DEFAULT_H7_FW_FN = os.path.join(BASEDIR, "board", "obj", "panda_h7.bin.signed") +DEFAULT_H7_BOOTSTUB_FN = os.path.join(BASEDIR, "board", "obj", "bootstub.panda_h7.bin") diff --git a/panda/python/dfu.py b/panda/python/dfu.py index e7d1d9151..317780ca8 100644 --- a/panda/python/dfu.py +++ b/panda/python/dfu.py @@ -1,10 +1,14 @@ -import os import usb1 import struct import binascii +from .config import BOOTSTUB_ADDRESS, APP_ADDRESS_H7, APP_ADDRESS_FX, BLOCK_SIZE_H7, BLOCK_SIZE_FX, DEFAULT_H7_BOOTSTUB_FN, DEFAULT_BOOTSTUB_FN + + +MCU_TYPE_F2 = 0 +MCU_TYPE_F4 = 1 +MCU_TYPE_H7 = 2 # *** DFU mode *** - DFU_DNLOAD = 1 DFU_UPLOAD = 2 DFU_GETSTATUS = 3 @@ -21,6 +25,7 @@ class PandaDFU(object): except Exception: continue if this_dfu_serial == dfu_serial or dfu_serial is None: + self._mcu_type = self.get_mcu_type(device) self._handle = device.open() return raise Exception("failed to open " + dfu_serial if dfu_serial is not None else "DFU device") @@ -41,11 +46,18 @@ class PandaDFU(object): return dfu_serials @staticmethod - def st_serial_to_dfu_serial(st): + def st_serial_to_dfu_serial(st, mcu_type=MCU_TYPE_F4): if st is None or st == "none": return None uid_base = struct.unpack("H" * 6, bytes.fromhex(st)) - return binascii.hexlify(struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4] + 0xA, uid_base[3])).upper().decode("utf-8") + if mcu_type == MCU_TYPE_H7: + return binascii.hexlify(struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4], uid_base[3])).upper().decode("utf-8") + else: + return binascii.hexlify(struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4] + 0xA, uid_base[3])).upper().decode("utf-8") + + # TODO: Find a way to detect F4 vs F2 + def get_mcu_type(self, dev): + return MCU_TYPE_H7 if dev.getbcdDevice() == 512 else MCU_TYPE_F4 def status(self): while 1: @@ -85,14 +97,17 @@ class PandaDFU(object): def program_bootstub(self, code_bootstub): self.clear_status() - self.erase(0x8004000) - self.erase(0x8000000) - self.program(0x8000000, code_bootstub, 0x800) + self.erase(BOOTSTUB_ADDRESS) + if self._mcu_type == MCU_TYPE_H7: + self.erase(APP_ADDRESS_H7) + self.program(BOOTSTUB_ADDRESS, code_bootstub, BLOCK_SIZE_H7) + else: + self.erase(APP_ADDRESS_FX) + self.program(BOOTSTUB_ADDRESS, code_bootstub, BLOCK_SIZE_FX) self.reset() def recover(self): - from panda import BASEDIR - fn = os.path.join(BASEDIR, "board", "obj", "bootstub.panda.bin") + fn = DEFAULT_H7_BOOTSTUB_FN if self._mcu_type == MCU_TYPE_H7 else DEFAULT_BOOTSTUB_FN with open(fn, "rb") as f: code = f.read() @@ -101,7 +116,7 @@ class PandaDFU(object): def reset(self): # **** Reset **** - self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, b"\x21" + struct.pack("I", 0x8000000)) + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, b"\x21" + struct.pack("I", BOOTSTUB_ADDRESS)) self.status() try: self._handle.controlWrite(0x21, DFU_DNLOAD, 2, 0, b"") diff --git a/release/files_common b/release/files_common index c227e5a64..512353242 100644 --- a/release/files_common +++ b/release/files_common @@ -275,6 +275,7 @@ selfdrive/hardware/hw.h selfdrive/hardware/eon/__init__.py selfdrive/hardware/eon/hardware.h selfdrive/hardware/eon/hardware.py +selfdrive/hardware/eon/androidd.py selfdrive/hardware/tici/__init__.py selfdrive/hardware/tici/hardware.py selfdrive/hardware/tici/amplifier.py @@ -310,7 +311,9 @@ selfdrive/logcatd/logcatd_android.cc selfdrive/logcatd/logcatd_systemd.cc selfdrive/proclogd/SConscript -selfdrive/proclogd/proclogd.cc +selfdrive/proclogd/main.cc +selfdrive/proclogd/proclog.cc +selfdrive/proclogd/proclog.h selfdrive/loggerd/SConscript selfdrive/loggerd/encoder.h @@ -502,6 +505,7 @@ cereal/log.capnp cereal/services.py cereal/SConscript cereal/include/** +cereal/logger/logger.h cereal/messaging/.gitignore cereal/messaging/__init__.py cereal/messaging/bridge.cc @@ -525,7 +529,6 @@ cereal/visionipc/*.pxd panda/.gitignore panda/__init__.py -panda/VERSION panda/board/** panda/certs/** panda/crypto/** diff --git a/release/files_tici b/release/files_tici index f3037a1d4..cf5184a58 100644 --- a/release/files_tici +++ b/release/files_tici @@ -1,5 +1,3 @@ -installer/continue_openpilot.sh - phonelibs/mapbox-gl-native-qt/include/* selfdrive/timezoned.py diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 86751fad8..4c656756b 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -22,6 +22,7 @@ from websocket import ABNF, WebSocketTimeoutException, WebSocketException, creat import cereal.messaging as messaging from cereal.services import service_list from common.api import Api +from common.file_helpers import CallbackReader from common.basedir import PERSIST from common.params import Params from common.realtime import sec_since_boot @@ -41,6 +42,7 @@ RECONNECT_TIMEOUT_S = 70 RETRY_DELAY = 10 # seconds MAX_RETRY_COUNT = 30 # Try for at most 5 minutes if upload fails immediately +WS_FRAME_SIZE = 4096 dispatcher["echo"] = lambda s: s recv_queue: Any = queue.Queue() @@ -49,7 +51,9 @@ upload_queue: Any = queue.Queue() log_send_queue: Any = queue.Queue() log_recv_queue: Any = queue.Queue() cancelled_uploads: Any = set() -UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id', 'retry_count'], defaults=(0,)) +UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id', 'retry_count', 'current', 'progress'], defaults=(0, False, 0)) + +cur_upload_items = {} def handle_long_poll(ws): @@ -100,35 +104,53 @@ def jsonrpc_handler(end_event): def upload_handler(end_event): + tid = threading.get_ident() + while not end_event.is_set(): + cur_upload_items[tid] = None + try: - item = upload_queue.get(timeout=1) - if item.id in cancelled_uploads: - cancelled_uploads.remove(item.id) + cur_upload_items[tid] = upload_queue.get(timeout=1)._replace(current=True) + if cur_upload_items[tid].id in cancelled_uploads: + cancelled_uploads.remove(cur_upload_items[tid].id) continue try: - _do_upload(item) - except (requests.exceptions.Timeout, requests.exceptions.ConnectionError, requests.exceptions.SSLError) as e: - cloudlog.warning(f"athena.upload_handler.retry {e} {item}") + def cb(sz, cur): + cur_upload_items[tid] = cur_upload_items[tid]._replace(progress=cur / sz if sz else 1) - if item.retry_count < MAX_RETRY_COUNT: - item = item._replace(retry_count=item.retry_count + 1) + _do_upload(cur_upload_items[tid], cb) + except (requests.exceptions.Timeout, requests.exceptions.ConnectionError, requests.exceptions.SSLError) as e: + cloudlog.warning(f"athena.upload_handler.retry {e} {cur_upload_items[tid]}") + + if cur_upload_items[tid].retry_count < MAX_RETRY_COUNT: + item = cur_upload_items[tid] + item = item._replace( + retry_count=item.retry_count + 1, + progress=0, + current=False + ) upload_queue.put_nowait(item) + cur_upload_items[tid] = None for _ in range(RETRY_DELAY): time.sleep(1) if end_event.is_set(): break + except queue.Empty: pass except Exception: cloudlog.exception("athena.upload_handler.exception") -def _do_upload(upload_item): +def _do_upload(upload_item, callback=None): with open(upload_item.path, "rb") as f: size = os.fstat(f.fileno()).st_size + + if callback: + f = CallbackReader(f, callback, size) + return requests.put(upload_item.url, data=f, headers={**upload_item.headers, 'Content-Length': str(size)}, @@ -171,11 +193,29 @@ def setNavDestination(latitude=0, longitude=0): return {"success": 1} -@dispatcher.add_method -def listDataDirectory(): - files = [os.path.relpath(os.path.join(dp, f), ROOT) for dp, dn, fn in os.walk(ROOT) for f in fn] +def scan_dir(path, prefix): + files = list() + # only walk directories that match the prefix + # (glob and friends traverse entire dir tree) + with os.scandir(path) as i: + for e in i: + rel_path = os.path.relpath(e.path, ROOT) + if e.is_dir(follow_symlinks=False): + # add trailing slash + rel_path = os.path.join(rel_path, '') + # if prefix is a partial dir name, current dir will start with prefix + # if prefix is a partial file name, prefix with start with dir name + if rel_path.startswith(prefix) or prefix.startswith(rel_path): + files.extend(scan_dir(e.path, prefix)) + else: + if rel_path.startswith(prefix): + files.append(rel_path) return files +@dispatcher.add_method +def listDataDirectory(prefix=''): + return scan_dir(ROOT, prefix) + @dispatcher.add_method def reboot(): @@ -212,7 +252,8 @@ def uploadFileToUrl(fn, url, headers): @dispatcher.add_method def listUploadQueue(): - return [item._asdict() for item in list(upload_queue.queue)] + items = list(upload_queue.queue) + list(cur_upload_items.values()) + return [i._asdict() for i in items if i is not None] @dispatcher.add_method @@ -466,7 +507,11 @@ def ws_send(ws, end_event): data = send_queue.get_nowait() except queue.Empty: data = log_send_queue.get(timeout=1) - ws.send(data) + for i in range(0, len(data), WS_FRAME_SIZE): + frame = data[i:i+WS_FRAME_SIZE] + last = i + WS_FRAME_SIZE >= len(data) + opcode = ABNF.OPCODE_TEXT if i == 0 else ABNF.OPCODE_CONT + ws.send_frame(ABNF.create_frame(frame, opcode, last)) except queue.Empty: pass except Exception: @@ -514,6 +559,8 @@ def main(): manage_tokens(api) conn_retries = 0 + cur_upload_items.clear() + handle_long_poll(ws) except (KeyboardInterrupt, SystemExit): break diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index a8e8ebecf..1cfff2008 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -445,9 +445,10 @@ void hardware_control_thread() { if (sm.updated("driverCameraState")) { auto event = sm["driverCameraState"]; int cur_integ_lines = event.getDriverCameraState().getIntegLines(); + float cur_gain = event.getDriverCameraState().getGain(); if (Hardware::TICI()) { - cur_integ_lines = integ_lines_filter.update(cur_integ_lines); + cur_integ_lines = integ_lines_filter.update(cur_integ_lines * cur_gain); } last_front_frame_t = event.getLogMonoTime(); diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index d75585065..7930a7d57 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -11,8 +11,10 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" -Panda::Panda() { +Panda::Panda(std::string serial) { // init libusb + ssize_t num_devices; + libusb_device **dev_list = NULL; int err = libusb_init(&ctx); if (err != 0) { goto fail; } @@ -22,8 +24,28 @@ Panda::Panda() { libusb_set_debug(ctx, 3); #endif - dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); - if (dev_handle == NULL) { goto fail; } + // connect by serial + num_devices = libusb_get_device_list(ctx, &dev_list); + if (num_devices < 0) { goto fail; } + for (size_t i = 0; i < num_devices; ++i) { + libusb_device_descriptor desc; + libusb_get_device_descriptor(dev_list[i], &desc); + if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) { + libusb_open(dev_list[i], &dev_handle); + if (dev_handle == NULL) { goto fail; } + + unsigned char desc_serial[25]; + int ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, sizeof(desc_serial)); + if (ret < 0) { goto fail; } + + if (serial.empty() || serial.compare(reinterpret_cast(desc_serial)) == 0) { + break; + } + libusb_close(dev_handle); + dev_handle = NULL; + } + } + libusb_free_device_list(dev_list, 1); if (libusb_kernel_driver_active(dev_handle, 0) == 1) { libusb_detach_kernel_driver(dev_handle, 0); @@ -47,6 +69,9 @@ Panda::Panda() { fail: cleanup(); + if (dev_list != NULL) { + libusb_free_device_list(dev_list, 1); + } throw std::runtime_error("Error connecting to panda"); } diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 92bd7fcf2..d3d929724 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -49,7 +49,7 @@ class Panda { void cleanup(); public: - Panda(); + Panda(std::string serial=""); ~Panda(); std::atomic connected = true; diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 4c19d1d81..89052e5e1 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -127,8 +127,6 @@ bool CameraBuf::acquire() { const size_t globalWorkSize[] = {size_t(camera_state->ci.frame_width), size_t(camera_state->ci.frame_height)}; const size_t localWorkSize[] = {DEBAYER_LOCAL_WORKSIZE, DEBAYER_LOCAL_WORKSIZE}; CL_CHECK(clSetKernelArg(krnl_debayer, 2, localMemSize, 0)); - int ggain = camera_state->analog_gain + 4*camera_state->dc_gain_enabled; - CL_CHECK(clSetKernelArg(krnl_debayer, 3, sizeof(int), &ggain)); CL_CHECK(clEnqueueNDRangeKernel(q, krnl_debayer, 2, NULL, globalWorkSize, localWorkSize, 0, 0, &debayer_event)); #else @@ -193,11 +191,11 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr } kj::Array get_frame_image(const CameraBuf *b) { - static const int x_min = getenv("XMIN") ? atoi(getenv("XMIN")) : 0; - static const int y_min = getenv("YMIN") ? atoi(getenv("YMIN")) : 0; - static const int env_xmax = getenv("XMAX") ? atoi(getenv("XMAX")) : -1; - static const int env_ymax = getenv("YMAX") ? atoi(getenv("YMAX")) : -1; - static const int scale = getenv("SCALE") ? atoi(getenv("SCALE")) : 1; + static const int x_min = util::getenv("XMIN", 0); + static const int y_min = util::getenv("YMIN", 0); + static const int env_xmax = util::getenv("XMAX", -1); + static const int env_ymax = util::getenv("YMAX", -1); + static const int scale = util::getenv("SCALE", 1); assert(b->cur_rgb_buf); @@ -280,39 +278,30 @@ static void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { free(thumbnail_buffer); } -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted) { - const uint8_t *pix_ptr = b->cur_yuv_buf->y; +float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip) { + int lum_med; uint32_t lum_binning[256] = {0}; + const uint8_t *pix_ptr = b->cur_yuv_buf->y; + unsigned int lum_total = 0; for (int y = y_start; y < y_end; y += y_skip) { for (int x = x_start; x < x_end; x += x_skip) { uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; - if (hist_ceil && lum < 80 && lum_binning[lum] > HISTO_CEIL_K * (y_end - y_start) * (x_end - x_start) / x_skip / y_skip / 256) { - continue; - } lum_binning[lum]++; lum_total += 1; } } + + // Find mean lumimance value unsigned int lum_cur = 0; - int lum_med = 0; - int lum_med_alt = 0; - for (lum_med=255; lum_med>=0; lum_med--) { + for (lum_med = 255; lum_med >= 0; lum_med--) { lum_cur += lum_binning[lum_med]; - if (hl_weighted) { - int lum_med_tmp = 0; - int hb = HLC_THRESH + (10 - analog_gain); - if (lum_cur > 0 && lum_med > hb) { - lum_med_tmp = (lum_med - hb) + 100; - } - lum_med_alt = lum_med_alt>lum_med_tmp?lum_med_alt:lum_med_tmp; - } + if (lum_cur >= lum_total / 2) { break; } } - lum_med = lum_med_alt>0 ? lum_med + lum_med/32*lum_cur*abs(lum_med_alt - lum_med)/lum_total:lum_med; return lum_med / 256.0; } @@ -355,18 +344,12 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; const CameraBuf *b = &c->buf; - bool hist_ceil = false, hl_weighted = false; int x_offset = 0, y_offset = 0; int frame_width = b->rgb_width, frame_height = b->rgb_height; -#ifndef QCOM2 - int analog_gain = -1; -#else - int analog_gain = c->analog_gain; -#endif + ExpRect def_rect; if (Hardware::TICI()) { - hist_ceil = hl_weighted = true; x_offset = 630, y_offset = 156; frame_width = 668, frame_height = frame_width / 1.33; def_rect = {96, 1832, 2, 242, 1148, 4}; @@ -377,7 +360,7 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { static ExpRect rect = def_rect; // use driver face crop for AE - if (sm.updated("driverState")) { + if (Hardware::EON() && sm.updated("driverState")) { if (auto state = sm["driverState"].getDriverState(); state.getFaceProb() > 0.4) { auto face_position = state.getFacePosition(); int x = is_rhd ? 0 : frame_width - (0.5 * frame_height); @@ -385,16 +368,15 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { int y = (face_position[1] + 0.5) * frame_height + y_offset; rect = {std::max(0, x - 72), std::min(b->rgb_width - 1, x + 72), 2, std::max(0, y - 72), std::min(b->rgb_height - 1, y + 72), 1}; - } else { - rect = def_rect; } } - camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip, analog_gain, hist_ceil, hl_weighted)); + camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); } void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt) { - if (cnt % 3 == 0) { + int j = Hardware::TICI() ? 1 : 3; + if (cnt % j == 0) { sm->update(0); driver_cam_auto_exposure(c, *sm); } diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 17051de40..bfa317b3c 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -27,16 +27,13 @@ #define CAMERA_ID_MAX 9 #define UI_BUF_COUNT 4 + #define LOG_CAMERA_ID_FCAMERA 0 #define LOG_CAMERA_ID_DCAMERA 1 #define LOG_CAMERA_ID_ECAMERA 2 #define LOG_CAMERA_ID_QCAMERA 3 #define LOG_CAMERA_ID_MAX 4 -#define HLC_THRESH 222 -#define HLC_A 80 -#define HISTO_CEIL_K 5 - const bool env_send_driver = getenv("SEND_DRIVER") != NULL; const bool env_send_road = getenv("SEND_ROAD") != NULL; const bool env_send_wide_road = getenv("SEND_WIDE_ROAD") != NULL; @@ -62,6 +59,7 @@ typedef struct LogCameraInfo { bool is_h265; bool downscale; bool has_qcamera; + bool trigger_rotate; } LogCameraInfo; typedef struct FrameMetadata { @@ -134,7 +132,7 @@ typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data); kj::Array get_frame_image(const CameraBuf *b); -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip, int analog_gain, bool hist_ceil, bool hl_weighted); +float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); void common_process_driver_camera(SubMaster *sm, PubMaster *pm, CameraState *c, int cnt); diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 5ac90e4b3..7b350215d 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -1113,7 +1113,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { if (cnt % 3 == 0) { const int x = 290, y = 322, width = 560, height = 314; const int skip = 1; - camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip, -1, false, false)); + camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip)); } } diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index ff512e658..9a2ef7393 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -22,18 +22,13 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/camerad/cameras/sensor2_i2c.h" -#define FRAME_WIDTH 1928 -#define FRAME_HEIGHT 1208 -//#define FRAME_STRIDE 1936 // for 8 bit output -#define FRAME_STRIDE 2416 // for 10 bit output -//#define FRAME_STRIDE 1936 // for 8 bit output - -#define MIPI_SETTLE_CNT 33 // Calculated by camera_freqs.py - extern ExitHandler do_exit; -// global var for AE ops -std::atomic cam_exp[3] = {{{0}}}; +const size_t FRAME_WIDTH = 1928; +const size_t FRAME_HEIGHT = 1208; +const size_t FRAME_STRIDE = 2416; // for 10 bit output + +const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py CameraInfo cameras_supported[CAMERA_ID_MAX] = { [CAMERA_ID_AR0231] = { @@ -46,17 +41,27 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { }, }; -float sensor_analog_gains[ANALOG_GAIN_MAX_IDX] = {3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, - 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, - 7.0/2.0, 8.0/2.0}; +const float DC_GAIN = 2.5; +const float sensor_analog_gains[] = { + 1.0/8.0, 2.0/8.0, 2.0/7.0, 3.0/7.0, // 0, 1, 2, 3 + 3.0/6.0, 4.0/6.0, 4.0/5.0, 5.0/5.0, // 4, 5, 6, 7 + 5.0/4.0, 6.0/4.0, 6.0/3.0, 7.0/3.0, // 8, 9, 10, 11 + 7.0/2.0, 8.0/2.0, 8.0/1.0}; // 12, 13, 14, 15 = bypass + +const int ANALOG_GAIN_MIN_IDX = 0x1; // 0.25x +const int ANALOG_GAIN_REC_IDX = 0x6; // 0.8x +const int ANALOG_GAIN_MAX_IDX = 0xD; // 4.0x + +const int EXPOSURE_TIME_MIN = 2; // with HDR, fastest ss +const int EXPOSURE_TIME_MAX = 1904; // with HDR, slowest ss // ************** low level camera helpers **************** - int 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; + if (size == 0) { + camcontrol.size = 8; camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; } else { camcontrol.size = size; @@ -104,7 +109,7 @@ void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, i assert(ptr != MAP_FAILED); } - // LOGD("alloced: %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); + // 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; } @@ -520,15 +525,17 @@ static void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, s->camera_num = camera_num; - s->dc_gain_enabled = false; - s->analog_gain = 0x5; - s->analog_gain_frac = sensor_analog_gains[s->analog_gain]; - s->exposure_time = 256; - s->exposure_time_max = 1.2 * EXPOSURE_TIME_MAX / 2; - s->exposure_time_min = 0.75 * EXPOSURE_TIME_MIN * 2; s->request_id_last = 0; s->skipped = true; - s->ef_filtered = 1.0; + + s->min_ev = EXPOSURE_TIME_MIN * sensor_analog_gains[ANALOG_GAIN_MIN_IDX]; + s->max_ev = EXPOSURE_TIME_MAX * sensor_analog_gains[ANALOG_GAIN_MAX_IDX] * DC_GAIN; + s->target_grey_fraction = 0.3; + + s->dc_gain_enabled = false; + s->gain_idx = ANALOG_GAIN_REC_IDX; + s->exposure_time = 5; + s->cur_ev[0] = s->cur_ev[1] = s->cur_ev[2] = (s->dc_gain_enabled ? DC_GAIN : 1) * sensor_analog_gains[s->gain_idx] * s->exposure_time; s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type); } @@ -905,7 +912,7 @@ void handle_camera_event(CameraState *s, void *evdat) { meta_data.frame_id = main_id - s->idx_offset; meta_data.timestamp_sof = timestamp; s->exp_lock.lock(); - meta_data.gain = s->dc_gain_enabled ? s->analog_gain_frac * 2.5 : s->analog_gain_frac; + meta_data.gain = s->dc_gain_enabled ? s->analog_gain_frac * DC_GAIN : s->analog_gain_frac; meta_data.high_conversion_gain = s->dc_gain_enabled; meta_data.integ_lines = s->exposure_time; meta_data.measured_grey_fraction = s->measured_grey_fraction; @@ -925,139 +932,113 @@ void handle_camera_event(CameraState *s, void *evdat) { } } -// ******************* exposure control helpers ******************* - -void set_exposure_time_bounds(CameraState *s) { - switch (s->analog_gain) { - case 0: { - s->exposure_time_min = EXPOSURE_TIME_MIN; - s->exposure_time_max = EXPOSURE_TIME_MAX; // EXPOSURE_TIME_MIN * 4; - break; - } - case ANALOG_GAIN_MAX_IDX - 1: { - s->exposure_time_min = EXPOSURE_TIME_MIN; // EXPOSURE_TIME_MAX / 4; - s->exposure_time_max = EXPOSURE_TIME_MAX; - break; - } - default: { - // finetune margins on both ends - float k_up = sensor_analog_gains[s->analog_gain+1] / sensor_analog_gains[s->analog_gain]; - float k_down = sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]; - s->exposure_time_min = k_down * EXPOSURE_TIME_MIN * 2; - s->exposure_time_max = k_up * EXPOSURE_TIME_MAX / 2; - } - } -} - -void switch_conversion_gain(CameraState *s) { - if (!s->dc_gain_enabled) { - s->dc_gain_enabled = true; - s->analog_gain -= 4; - } else { - s->dc_gain_enabled = false; - s->analog_gain += 4; - } -} - static void set_camera_exposure(CameraState *s, float grey_frac) { - // TODO: get stats from sensor? - float target_grey = 0.4 - ((float)(s->analog_gain + 4*s->dc_gain_enabled) / 48.0f); - float exposure_factor = 1 + 30 * pow((target_grey - grey_frac), 3); - exposure_factor = std::max(exposure_factor, 0.56f); + const float dt = 0.05; - if (s->camera_num != 1) { - s->ef_filtered = (1 - EF_LOWPASS_K) * s->ef_filtered + EF_LOWPASS_K * exposure_factor; - exposure_factor = s->ef_filtered; + const float ts_grey = 10.0; + const float ts_ev = 0.05; + + const float k_grey = (dt / ts_grey) / (1.0 + dt / ts_grey); + const float k_ev = (dt / ts_ev) / (1.0 + dt / ts_ev); + + // It takes 3 frames for the commanded exposure settings to take effect. The first frame is already started by the time + // we reach this function, the other 2 are due to the register buffering in the sensor. + // 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 outputed by the sensor we can do AE before the debayering is complete + + const float cur_ev = s->cur_ev[s->buf.cur_frame_data.frame_id % 3]; + + // Scale target grey between 0.1 and 0.4 depending on lighting conditions + float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + cur_ev) / log2(6000.0), 0.1, 0.4); + float target_grey = (1.0 - k_grey) * s->target_grey_fraction + k_grey * new_target_grey; + + float desired_ev = std::clamp(cur_ev * target_grey / grey_frac, s->min_ev, s->max_ev); + float k = (1.0 - k_ev) / 3.0; + desired_ev = (k * s->cur_ev[0]) + (k * s->cur_ev[1]) + (k * s->cur_ev[2]) + (k_ev * desired_ev); + + float best_ev_score = 1e6; + int new_g = 0; + int new_t = 0; + + // 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 = s->dc_gain_enabled; + if (!enable_dc_gain && target_grey < 0.2) { + enable_dc_gain = true; + } else if (enable_dc_gain && target_grey > 0.3) { + enable_dc_gain = false; + } + + // Simple brute force optimizer to choose sensor parameters + // to reach desired EV + for (int g = std::max((int)ANALOG_GAIN_MIN_IDX, s->gain_idx - 1); g <= std::min((int)ANALOG_GAIN_MAX_IDX, s->gain_idx + 1); g++) { + float gain = sensor_analog_gains[g] * (enable_dc_gain ? DC_GAIN : 1); + + // Compute optimal time for given gain + int t = std::clamp(int(std::round(desired_ev / gain)), EXPOSURE_TIME_MIN, EXPOSURE_TIME_MAX); + + // Only go below recomended gain when absolutely necessary to not overexpose + if (g < ANALOG_GAIN_REC_IDX && t > 20 && g < s->gain_idx) { + continue; + } + + // Compute error to desired ev + float score = std::abs(desired_ev - (t * gain)) * 10; + + // Going below recomended gain needs lower penalty to not overexpose + float m = g > ANALOG_GAIN_REC_IDX ? 5.0 : 0.1; + score += std::abs(g - (int)ANALOG_GAIN_REC_IDX) * m; + + // LOGE("cam: %d - gain: %d, t: %d (%.2f), score %.2f, score + gain %.2f, %.3f, %.3f", s->camera_num, g, t, desired_ev / gain, score, score + std::abs(g - s->gain_idx) * (score + 1.0) / 10.0, desired_ev, s->min_ev); + + // Small penalty on changing gain + score += std::abs(g - s->gain_idx) * (score + 1.0) / 10.0; + + if (score < best_ev_score) { + new_t = t; + new_g = g; + best_ev_score = score; + } } s->exp_lock.lock(); + s->measured_grey_fraction = grey_frac; s->target_grey_fraction = target_grey; - // always prioritize exposure time adjust - s->exposure_time *= exposure_factor; + s->analog_gain_frac = sensor_analog_gains[new_g]; + s->gain_idx = new_g; + s->exposure_time = new_t; + s->dc_gain_enabled = enable_dc_gain; - // switch gain if max/min exposure time is reached - // or always switch down to a lower gain when possible - bool kd = false; - if (s->analog_gain > 0) { - kd = 1.1 * s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]) < EXPOSURE_TIME_MAX / 2; - } - - if (s->exposure_time > s->exposure_time_max) { - if (s->analog_gain < ANALOG_GAIN_MAX_IDX - 1) { - s->exposure_time = EXPOSURE_TIME_MAX / 2; - s->analog_gain += 1; - if (!s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] >= 4.0) { // switch to HCG - switch_conversion_gain(s); - } - set_exposure_time_bounds(s); - } else { - s->exposure_time = s->exposure_time_max; - } - } else if (s->exposure_time < s->exposure_time_min || kd) { - if (s->analog_gain > 0) { - s->exposure_time = std::max(EXPOSURE_TIME_MIN * 2, (int)(s->exposure_time / (sensor_analog_gains[s->analog_gain-1] / sensor_analog_gains[s->analog_gain]))); - s->analog_gain -= 1; - if (s->dc_gain_enabled && sensor_analog_gains[s->analog_gain] <= 1.25) { // switch back to LCG - switch_conversion_gain(s); - } - set_exposure_time_bounds(s); - } else { - s->exposure_time = s->exposure_time_min; - } - } - - // set up config - uint16_t AG = s->analog_gain + 4; - AG = 0xFF00 + AG * 16 + AG; - s->analog_gain_frac = sensor_analog_gains[s->analog_gain]; + float gain = s->analog_gain_frac * (s->dc_gain_enabled ? DC_GAIN : 1.0); + s->cur_ev[s->buf.cur_frame_data.frame_id % 3] = s->exposure_time * gain; s->exp_lock.unlock(); - // printf("cam %d, min %d, max %d \n", s->camera_num, s->exposure_time_min, s->exposure_time_max); - // printf("cam %d, set AG to 0x%X, S to %d, dc %d \n", s->camera_num, AG, s->exposure_time, s->dc_gain_enabled); + // 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() - s->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", s->camera_num, 1e-9 * nanos_since_boot(), 1e-9 * s->buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - s->buf.cur_frame_data.timestamp_sof)); + + uint16_t analog_gain_reg = 0xFF00 | (new_g << 4) | new_g; struct i2c_random_wr_payload exp_reg_array[] = { - {0x3366, AG}, // analog gain - {0x3362, (uint16_t)(s->dc_gain_enabled?0x1:0x0)}, // DC_GAIN - {0x305A, 0x00F8}, // red gain - {0x3058, 0x0122}, // blue gain - {0x3056, 0x009A}, // g1 gain - {0x305C, 0x009A}, // g2 gain - {0x3012, (uint16_t)s->exposure_time}, // integ time - }; - //{0x301A, 0x091C}}; // reset + {0x3366, analog_gain_reg}, + {0x3362, (uint16_t)(s->dc_gain_enabled ? 0x1 : 0x0)}, + {0x3012, (uint16_t)s->exposure_time}, + }; sensors_i2c(s, exp_reg_array, sizeof(exp_reg_array)/sizeof(struct i2c_random_wr_payload), - CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); + CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); + } void camera_autoexposure(CameraState *s, float grey_frac) { - CameraExpInfo tmp = cam_exp[s->camera_num].load(); - tmp.op_id++; - tmp.grey_frac = grey_frac; - cam_exp[s->camera_num].store(tmp); + set_camera_exposure(s, grey_frac); } -static void ae_thread(MultiCameraState *s) { - CameraState *c_handles[3] = {&s->wide_road_cam, &s->road_cam, &s->driver_cam}; - - int op_id_last[3] = {0}; - CameraExpInfo cam_op[3]; - - set_thread_name("camera_settings"); - - while(!do_exit) { - for (int i=0;i<3;i++) { - cam_op[i] = cam_exp[i].load(); - if (cam_op[i].op_id != op_id_last[i]) { - set_camera_exposure(c_handles[i], cam_op[i].grey_frac); - op_id_last[i] = cam_op[i].op_id; - } - } - - util::sleep_for(50); - } -} void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { common_process_driver_camera(s->sm, s->pm, c, cnt); @@ -1078,17 +1059,14 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { } s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); - if (cnt % 3 == 0) { - const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); - const int skip = 2; - camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip, (int)c->analog_gain, true, true)); - } + const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); + const int skip = 2; + camera_autoexposure(c, set_exposure_target(b, x, x + w, skip, y, y + h, skip)); } void cameras_run(MultiCameraState *s) { LOG("-- Starting threads"); std::vector threads; - threads.push_back(std::thread(ae_thread, s)); threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); threads.push_back(start_process_thread(s, &s->driver_cam, process_driver_camera)); threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h index 469a2f858..c7dd59787 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ b/selfdrive/camerad/cameras/camera_qcom2.h @@ -10,30 +10,23 @@ #include "selfdrive/common/util.h" #define FRAME_BUF_COUNT 4 - -#define ANALOG_GAIN_MAX_IDX 10 // 0xF is bypass -#define EXPOSURE_TIME_MIN 2 // with HDR, fastest ss -#define EXPOSURE_TIME_MAX 1904 // with HDR, slowest ss - -#define EF_LOWPASS_K 0.35 - #define DEBAYER_LOCAL_WORKSIZE 16 - typedef struct CameraState { MultiCameraState *multi_cam_state; CameraInfo ci; std::mutex exp_lock; - float analog_gain_frac; - uint16_t analog_gain; - bool dc_gain_enabled; + int exposure_time; - int exposure_time_min; - int exposure_time_max; - float ef_filtered; + bool dc_gain_enabled; + float analog_gain_frac; + + float cur_ev[3]; + float min_ev, max_ev; float measured_grey_fraction; float target_grey_fraction; + int gain_idx; unique_fd sensor_fd; unique_fd csiphy_fd; diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 10cb5ae76..fe6a99f37 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -26,9 +26,9 @@ half mf(half x, half cp) { } } -half3 color_correct(half3 rgb, int ggain) { +half3 color_correct(half3 rgb) { half3 ret = (0,0,0); - half cpx = 0.01; //clamp(0.01h, 0.05h, cpxb + cpxk * min(10, ggain)); + half cpx = 0.01; ret += (half)rgb.x * color_correction[0]; ret += (half)rgb.y * color_correction[1]; ret += (half)rgb.z * color_correction[2]; @@ -89,8 +89,7 @@ half phi(half x) { __kernel void debayer10(const __global uchar * in, __global uchar * out, - __local half * cached, - uint ggain + __local half * cached ) { const int x_global = get_global_id(0); @@ -200,10 +199,9 @@ __kernel void debayer10(const __global uchar * in, } rgb = clamp(0.0h, 1.0h, rgb); - rgb = color_correct(rgb, (int)ggain); + rgb = color_correct(rgb); out[out_idx + 0] = (uchar)(rgb.z); out[out_idx + 1] = (uchar)(rgb.y); out[out_idx + 2] = (uchar)(rgb.x); - } diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index 38a05820f..c3d8861a9 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -14,13 +14,19 @@ struct i2c_random_wr_payload init_array_ar0231[] = { // FORMAT {0x3040, 0xC000}, // READ_MODE - {0x3004, 0x0000}, // X_ADDR_START_ - {0x3008, 0x0787}, // X_ADDR_END_ - {0x3002, 0x0000}, // Y_ADDR_START_ - {0x3006, 0x04B7}, // Y_ADDR_END_ + {0x3004, 0x0000}, // X_ADDR_START_ (A) + {0x308A, 0x0000}, // X_ADDR_START_ (B) + {0x3008, 0x0787}, // X_ADDR_END_ (A) + {0x308E, 0x0787}, // X_ADDR_END_ (B) + {0x3002, 0x0000}, // Y_ADDR_START_ (A) + {0x308C, 0x0000}, // Y_ADDR_START_ (B) + {0x3006, 0x04B7}, // Y_ADDR_END_ (A) + {0x3090, 0x04B7}, // Y_ADDR_END_ (B) {0x3032, 0x0000}, // SCALING_MODE - {0x30A2, 0x0001}, // X_ODD_INC_ - {0x30A6, 0x0001}, // Y_ODD_INC_ + {0x30A2, 0x0001}, // X_ODD_INC_ (A) + {0x30AE, 0x0001}, // X_ODD_INC_ (B) + {0x30A6, 0x0001}, // Y_ODD_INC_ (A) + {0x30A8, 0x0001}, // Y_ODD_INC_ (B) {0x3402, 0x0F10}, // X_OUTPUT_CONTROL {0x3404, 0x0970}, // Y_OUTPUT_CONTROL {0x3064, 0x1802}, // SMIA_TEST @@ -32,8 +38,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x340C, 0x802}, // 2 // 0000 0000 0010 // Readout timing - {0x300C, 0x07B9}, // LINE_LENGTH_PCK - {0x300A, 0x07E7}, // FRAME_LENGTH_LINES + {0x300C, 0x07B9}, // LINE_LENGTH_PCK (A) + {0x303E, 0x07B9}, // LINE_LENGTH_PCK (B) + {0x300A, 0x07E7}, // FRAME_LENGTH_LINES (A) + {0x30AA, 0x07E7}, // FRAME_LENGTH_LINES (B) {0x3042, 0x0000}, // EXTRA_DELAY // Readout Settings @@ -49,7 +57,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x3350, 0x0311}, // MIPI_F4_VDT_VC {0x31B0, 0x0053}, // FRAME_PREAMBLE {0x31B2, 0x003B}, // LINE_PREAMBLE - {0x301A, 0x01C}, // RESET_REGISTER + {0x301A, 0x001C}, // RESET_REGISTER // Noise Corrections {0x3092, 0x0C24}, // ROW_NOISE_CONTROL @@ -62,10 +70,18 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x31E0, 0x0003}, // HDR Settings - {0x3082, 0x0004}, // OPERATION_MODE_CTRL - {0x3238, 0x0004}, // EXPOSURE_RATIO - {0x3014, 0x098E}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x098E}, // FINE_INTEGRATION_TIME2 + {0x3082, 0x0004}, // OPERATION_MODE_CTRL (A) + {0x3084, 0x0004}, // OPERATION_MODE_CTRL (B) + + {0x3238, 0x0004}, // EXPOSURE_RATIO (A) + {0x323A, 0x0004}, // EXPOSURE_RATIO (B) + + {0x3014, 0x098E}, // FINE_INTEGRATION_TIME_ (A) + {0x3018, 0x098E}, // FINE_INTEGRATION_TIME_ (B) + + {0x321E, 0x098E}, // FINE_INTEGRATION_TIME2 (A) + {0x3220, 0x098E}, // FINE_INTEGRATION_TIME2 (B) + {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? {0x33DA, 0x0000}, // COMPANDING {0x318E, 0x0200}, // PRE_HDR_GAIN_EN @@ -82,16 +98,27 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x328E, 0x0FA0}, // T2 G2 // Initial Gains - {0x3022, 0x01}, // GROUPED_PARAMETER_HOLD_ - {0x3366, 0x5555}, // ANALOG_GAIN + {0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_ + {0x3366, 0xFF77}, // ANALOG_GAIN (1x) (A) + {0x3368, 0xFF77}, // ANALOG_GAIN (1x) (B) + {0x3060, 0x3333}, // ANALOG_COLOR_GAIN - {0x3362, 0x0000}, // DC GAIN - {0x305A, 0x0108}, // RED_GAIN - {0x3058, 0x00FB}, // BLUE_GAIN - {0x3056, 0x009A}, // GREEN1_GAIN - {0x305C, 0x009A}, // GREEN2_GAIN - {0x3022, 0x00}, // GROUPED_PARAMETER_HOLD_ + + {0x3362, 0x0000}, // DC GAIN (A & B) + + {0x305A, 0x00F8}, // red gain (A) + {0x3058, 0x0122}, // blue gain (A) + {0x3056, 0x009A}, // g1 gain (A) + {0x305C, 0x009A}, // g2 gain (A) + + {0x30C0, 0x00F8}, // red gain (B) + {0x30BE, 0x0122}, // blue gain (B) + {0x30BC, 0x009A}, // g1 gain (B) + {0x30C2, 0x009A}, // g2 gain (B) + + {0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_ // Initial Integration Time - {0x3012, 0x256}, + {0x3012, 0x0005}, // (A) + {0x3016, 0x0005}, // (B) }; diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index d3057c28b..4cb874d2d 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -253,7 +253,7 @@ def match_fw_to_car(fw_versions, allow_fuzzy=True): def get_fw_versions(logcan, sendcan, bus, extra=None, timeout=0.1, debug=False, progress=False): ecu_types = {} - # Extract ECU adresses to query from fingerprints + # Extract ECU addresses to query from fingerprints # ECUs using a subadress need be queried one by one, the rest can be done in parallel addrs = [] parallel_addrs = [] diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index 3f43fc581..0d26a1885 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -5,17 +5,18 @@ from selfdrive.controls.lib.drive_helpers import rate_limit from common.numpy_fast import clip, interp from selfdrive.car import create_gas_command from selfdrive.car.honda import hondacan -from selfdrive.car.honda.values import CruiseButtons, CAR, VISUAL_HUD, HONDA_BOSCH, CarControllerParams +from selfdrive.car.honda.values import OLD_NIDEC_LONG_CONTROL, CruiseButtons, CAR, VISUAL_HUD, HONDA_BOSCH, CarControllerParams from opendbc.can.packer import CANPacker VisualAlert = car.CarControl.HUDControl.VisualAlert +# TODO: not clear this does anything useful def actuator_hystereses(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 + 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: @@ -72,7 +73,7 @@ def process_hud_alert(hud_alert): HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "car", + ["pcm_accel", "v_cruise", "car", "lanes", "fcw", "acc_alert", "steer_required"]) @@ -84,7 +85,6 @@ class CarController(): self.apply_brake_last = 0 self.last_pump_ts = 0. self.packer = CANPacker(dbc_name) - self.new_radar_config = False self.params = CarControllerParams(CP) @@ -125,8 +125,6 @@ class CarController(): fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car, - hud_lanes, fcw_display, acc_alert, steer_required) # **** process the car messages **** @@ -148,10 +146,35 @@ class CarController(): can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, lkas_active, CS.CP.carFingerprint, idx, CS.CP.openpilotLongitudinalControl)) - # Send dashboard UI commands. - if (frame % 10) == 0: - idx = (frame//10) % 4 - can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, CS.is_metric, idx, CS.CP.openpilotLongitudinalControl, CS.stock_hud)) + + accel = actuators.gas - actuators.brake + + # TODO: pass in LoC.long_control_state and use that to decide starting/stoppping + stopping = accel < 0 and CS.out.vEgo < 0.3 + starting = accel > 0 and CS.out.vEgo < 0.3 + + # Prevent rolling backwards + accel = -1.0 if stopping else accel + if CS.CP.carFingerprint in HONDA_BOSCH: + apply_accel = interp(accel, P.BOSCH_ACCEL_LOOKUP_BP, P.BOSCH_ACCEL_LOOKUP_V) + else: + apply_accel = interp(accel, P.NIDEC_ACCEL_LOOKUP_BP, P.NIDEC_ACCEL_LOOKUP_V) + + # 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]) + if CS.CP.carFingerprint in OLD_NIDEC_LONG_CONTROL: + #pcm_speed = pcm_speed + pcm_accel = int(clip(pcm_accel, 0, 1) * 0xc6) + else: + max_accel = interp(CS.out.vEgo, P.NIDEC_MAX_ACCEL_BP, P.NIDEC_MAX_ACCEL_V) + pcm_accel = int(clip(apply_accel/max_accel, 0.0, 1.0) * 0xc6) + pcm_speed_BP = [-wind_brake, + -wind_brake*(3/4), + 0.0] + pcm_speed_V = [0.0, + clip(CS.out.vEgo + apply_accel/2.0 - 2.0, 0.0, 100.0), + clip(CS.out.vEgo + apply_accel/2.0 + 2.0, 0.0, 100.0)] + pcm_speed = interp(accel, pcm_speed_BP, pcm_speed_V) if not CS.CP.openpilotLongitudinalControl: if (frame % 2) == 0: @@ -168,31 +191,33 @@ class CarController(): if (frame % 2) == 0: idx = frame // 2 ts = frame * DT_CTRL + if CS.CP.carFingerprint in HONDA_BOSCH: - accel = actuators.gas - actuators.brake - - # TODO: pass in LoC.long_control_state and use that to decide starting/stoppping - stopping = accel < 0 and CS.out.vEgo < 0.3 - starting = accel > 0 and CS.out.vEgo < 0.3 - - # Prevent rolling backwards - accel = -1.0 if stopping else accel - - apply_accel = interp(accel, P.BOSCH_ACCEL_LOOKUP_BP, P.BOSCH_ACCEL_LOOKUP_V) apply_gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V) can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, apply_accel, apply_gas, idx, stopping, starting, CS.CP.carFingerprint)) else: - apply_gas = clip(actuators.gas, 0., 1.) - apply_brake = int(clip(self.brake_last * P.BRAKE_MAX, 0, P.BRAKE_MAX - 1)) + apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) + apply_brake = int(clip(apply_brake * P.BRAKE_MAX, 0, P.BRAKE_MAX - 1)) pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, - pcm_override, pcm_cancel_cmd, hud.fcw, idx, CS.CP.carFingerprint, CS.stock_brake)) + pcm_override, pcm_cancel_cmd, fcw_display, idx, CS.CP.carFingerprint, CS.stock_brake)) self.apply_brake_last = apply_brake if CS.CP.enableGasInterceptor: + # way too aggressive at low speed without this + gas_mult = interp(CS.out.vEgo, [0., 10.], [0.4, 1.0]) # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. # This prevents unexpected pedal range rescaling + apply_gas = clip(gas_mult * actuators.gas, 0., 1.) can_sends.append(create_gas_command(self.packer, apply_gas, idx)) + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car, + hud_lanes, fcw_display, acc_alert, steer_required) + + # Send dashboard UI commands. + if (frame % 10) == 0: + idx = (frame//10) % 4 + can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, CS.is_metric, idx, CS.CP.openpilotLongitudinalControl, CS.stock_hud)) + return can_sends diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 3067c5e29..36461bf82 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -11,7 +11,7 @@ TransmissionType = car.CarParams.TransmissionType def calc_cruise_offset(offset, speed): - # euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed + # heuristic formula so that speed is controlled to ~ 0.3m/s below pid_speed # constraints to solve for _K0, _K1, _K2 are: # - speed = 0m/s, out = -0.3 # - speed = 34m/s, offset = 20, out = -0.25 @@ -119,7 +119,7 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"): else: checks += [("CRUISE_PARAMS", 50)] - if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G): + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G): signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)] elif CP.carFingerprint == CAR.ODYSSEY_CHN: signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1)] @@ -230,7 +230,7 @@ class CarState(CarStateBase): # ******************* parse out can ******************* # TODO: find wheels moving bit in dbc - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G): + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G): ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 0.1 ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) elif self.CP.carFingerprint == CAR.ODYSSEY_CHN: @@ -257,7 +257,7 @@ class CarState(CarStateBase): self.brake_error = cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"] ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 - speed_factor = SPEED_FACTOR[self.CP.carFingerprint] + speed_factor = SPEED_FACTOR.get(self.CP.carFingerprint, 1.) ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"] * CV.KPH_TO_MS * speed_factor ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"] * CV.KPH_TO_MS * speed_factor ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"] * CV.KPH_TO_MS * speed_factor @@ -279,7 +279,7 @@ class CarState(CarStateBase): 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) self.brake_hold = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] - if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G): self.park_brake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 main_on = cp.vl["SCM_FEEDBACK"]["MAIN_ON"] @@ -311,7 +311,7 @@ class CarState(CarStateBase): 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[self.CP.carFingerprint] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) if self.CP.carFingerprint in HONDA_BOSCH: if not self.CP.openpilotLongitudinalControl: diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 883d4fe94..290d10028 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -1,7 +1,7 @@ from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from selfdrive.swaglog import cloudlog +from selfdrive.car.honda.values import HONDA_BOSCH, HONDA_BOSCH_EXT, CAR from selfdrive.config import Conversions as CV -from selfdrive.car.honda.values import HONDA_BOSCH +from selfdrive.swaglog import cloudlog # CAN bus layout with relay # 0 = ACC-CAN - radar side @@ -169,12 +169,18 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, lkas_hud_values = { 'SET_ME_X41': 0x41, - 'SET_ME_X48': 0x48, 'STEERING_REQUIRED': hud.steer_required, 'SOLID_LANES': hud.lanes, 'BEEP': 0, } - commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values, idx)) + if car_fingerprint not in HONDA_BOSCH_EXT: + lkas_hud_values['SET_ME_X48'] = 0x48 + + if car_fingerprint in HONDA_BOSCH_EXT and not openpilot_longitudinal_control: + commands.append(packer.make_can_msg('LKAS_HUD_A', bus_lkas, lkas_hud_values, idx)) + commands.append(packer.make_can_msg('LKAS_HUD_B', bus_lkas, lkas_hud_values, idx)) + else: + commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values, idx)) if radar_disabled and car_fingerprint in HONDA_BOSCH: radar_hud_values = { @@ -182,6 +188,9 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, is_metric, idx, } commands.append(packer.make_can_msg('RADAR_HUD', bus_pt, radar_hud_values, idx)) + if car_fingerprint == CAR.CIVIC_BOSCH: + commands.append(packer.make_can_msg("LEGACY_BRAKE_COMMAND", bus_pt, {}, idx)) + return commands diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 15446623c..6d583a26b 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -1,14 +1,13 @@ #!/usr/bin/env python3 -import numpy as np from cereal import car from panda import Panda -from common.numpy_fast import clip, interp +from common.numpy_fast import interp from common.params import Params -from selfdrive.config import Conversions as CV from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CAR, HONDA_BOSCH, HONDA_BOSCH_ALT_BRAKE_SIGNAL from selfdrive.car.honda.hondacan import disable_radar from selfdrive.car import STD_CARGO_KG, CivicParams, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint from selfdrive.car.interfaces import CarInterfaceBase +from selfdrive.config import Conversions as CV ButtonType = car.CarState.ButtonEvent.Type @@ -29,58 +28,17 @@ def compute_gb_honda_nidec(accel, speed): return float(accel) / 4.8 - creep_brake -def get_compute_gb_acura(): - # generate a function that takes in [desired_accel, current_speed] -> [-1.0, 1.0] - # where -1.0 is max brake and 1.0 is max gas - # see debug/dump_accel_from_fiber.py to see how those parameters were generated - w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], - [ 1.03691769, 0.78210306, -0.41343188]]) - b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) - w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], - [ 0.79973811, 0.13178682, 0.08550351], - [-0.15651935, -0.44360259, 0.76910877]]) - b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) - w4 = np.array([[-0.31521443], - [-0.38626176], - [ 0.52667892]]) - b4 = np.array([-0.02922216]) - - def compute_output(dat, w0, b0, w2, b2, w4, b4): - m0 = np.dot(dat, w0) + b0 - m0 = leakyrelu(m0, 0.1) - m2 = np.dot(m0, w2) + b2 - m2 = leakyrelu(m2, 0.1) - m4 = np.dot(m2, w4) + b4 - return m4 - - def leakyrelu(x, alpha): - return np.maximum(x, alpha * x) - - def _compute_gb_acura(accel, speed): - # linearly extrap below v1 using v1 and v2 data - v1 = 5. - v2 = 10. - dat = np.array([accel, speed]) - if speed > 5.: - m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) - else: - dat[1] = v1 - m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) - dat[1] = v2 - m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) - m4 = (speed - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 - return float(m4) - - return _compute_gb_acura +def compute_gb_acura(accel, speed): + GB_VALUES = [-2., 0.0, 0.8] + GB_BP = [-5., 0.0, 4.0] + return interp(accel, GB_BP, GB_VALUES) class CarInterface(CarInterfaceBase): def __init__(self, CP, CarController, CarState): super().__init__(CP, CarController, CarState) - if self.CS.CP.carFingerprint == CAR.ACURA_ILX: - self.compute_gb = get_compute_gb_acura() - elif self.CS.CP.carFingerprint in HONDA_BOSCH: + if self.CS.CP.carFingerprint in HONDA_BOSCH: self.compute_gb = compute_gb_honda_bosch else: self.compute_gb = compute_gb_honda_nidec @@ -159,6 +117,12 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward + # 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: @@ -184,11 +148,6 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] tire_stiffness_factor = 1. - ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5] - ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.54, 0.36] - elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL): stop_and_go = True ret.mass = CivicParams.MASS @@ -198,12 +157,8 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 1. ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - 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] - elif candidate in (CAR.ACCORD, CAR.ACCORDH): + elif candidate in (CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021): stop_and_go = True ret.mass = 3279. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.83 @@ -211,10 +166,6 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.33 # 11.82 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.8467 - 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] if eps_modified: ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] @@ -230,10 +181,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.72 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - 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] elif candidate in (CAR.CRV, CAR.CRV_EU): stop_and_go = False @@ -244,10 +191,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - 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] elif candidate == CAR.CRV_5G: stop_and_go = True @@ -265,10 +208,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] tire_stiffness_factor = 0.677 - 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] elif candidate == CAR.CRV_HYBRID: stop_and_go = True @@ -279,10 +218,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.677 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - 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] elif candidate == CAR.FIT: stop_and_go = False @@ -293,10 +228,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.75 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - 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] elif candidate == CAR.HRV: stop_and_go = False @@ -307,10 +238,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] tire_stiffness_factor = 0.5 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] - 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] elif candidate == CAR.ACURA_RDX: stop_and_go = False @@ -321,10 +248,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - 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] elif candidate == CAR.ACURA_RDX_3G: stop_and_go = True @@ -335,10 +258,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] tire_stiffness_factor = 0.677 - 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] elif candidate == CAR.ODYSSEY: stop_and_go = False @@ -349,10 +268,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - 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] elif candidate == CAR.ODYSSEY_CHN: stop_and_go = False @@ -363,10 +278,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - 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] elif candidate in (CAR.PILOT, CAR.PILOT_2019): stop_and_go = False @@ -377,10 +288,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - 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] elif candidate == CAR.RIDGELINE: stop_and_go = False @@ -391,10 +298,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - 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] elif candidate == CAR.INSIGHT: stop_and_go = True @@ -405,10 +308,6 @@ class CarInterface(CarInterfaceBase): ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - 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] else: raise ValueError("unsupported car %s" % candidate) @@ -441,7 +340,7 @@ class CarInterface(CarInterfaceBase): ret.brakeMaxV = [1.] # max brake allowed, 3.5m/s^2 else: ret.gasMaxBP = [0.] # m/s - ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed + ret.gasMaxV = [0.6] # max gas allowed ret.brakeMaxBP = [5., 20.] # m/s ret.brakeMaxV = [1., 0.8] # max brake allowed @@ -559,14 +458,12 @@ class CarInterface(CarInterfaceBase): else: hud_v_cruise = 255 - pcm_accel = int(clip(c.cruiseControl.accelOverride, 0, 1) * 0xc6) - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.speedOverride, c.cruiseControl.override, c.cruiseControl.cancel, - pcm_accel, + c.cruiseControl.accelOverride, hud_v_cruise, c.hudControl.lanesVisible, hud_show_car=c.hudControl.leadVisible, diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 289fab9f8..fe6f51546 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from cereal import car from selfdrive.car import dbc_dict @@ -10,18 +8,25 @@ class CarControllerParams(): ACCEL_MAX = 1.6 def __init__(self, CP): - self.BRAKE_MAX = 1024//4 - 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) + self.BRAKE_MAX = 1024//4 + 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) - self.BOSCH_ACCEL_LOOKUP_BP = [-1., 0., 0.6] - self.BOSCH_ACCEL_LOOKUP_V = [-3.5, 0., 2.] - self.BOSCH_GAS_LOOKUP_BP = [0., 0.6] - self.BOSCH_GAS_LOOKUP_V = [0, 2000] + self.NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] + self.NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] + + self.NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] + self.NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] + + + self.BOSCH_ACCEL_LOOKUP_BP = [-1., 0., 0.6] + self.BOSCH_ACCEL_LOOKUP_V = [-3.5, 0., 2.] + self.BOSCH_GAS_LOOKUP_BP = [0., 0.6] + self.BOSCH_GAS_LOOKUP_V = [0, 2000] # Car button codes @@ -31,7 +36,7 @@ class CruiseButtons: CANCEL = 2 MAIN = 1 -# See dbc files for info on values" +# See dbc files for info on values VISUAL_HUD = { VisualAlert.none: 0, VisualAlert.fcw: 1, @@ -40,11 +45,14 @@ VISUAL_HUD = { VisualAlert.brakePressed: 10, VisualAlert.wrongGear: 6, VisualAlert.seatbeltUnbuckled: 5, - VisualAlert.speedTooHigh: 8} + VisualAlert.speedTooHigh: 8 +} class CAR: ACCORD = "HONDA ACCORD 2018" ACCORDH = "HONDA ACCORD HYBRID 2018" + ACCORD_2021 = "HONDA ACCORD 2021" + ACCORDH_2021 = "HONDA ACCORD HYBRID 2021" CIVIC = "HONDA CIVIC 2016" CIVIC_BOSCH = "HONDA CIVIC (BOSCH) 2019" CIVIC_BOSCH_DIESEL = "HONDA CIVIC SEDAN 1.6 DIESEL 2019" @@ -71,7 +79,6 @@ FINGERPRINTS = { CAR.ACCORDH: [{ 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 525: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 }], - # Acura RDX w/ Added Comma Pedal Support (512L & 513L) CAR.ACURA_RDX: [{ 57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 342: 6, 344: 8, 380: 8, 392: 6, 398: 3, 399: 6, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, 1424: 5, 1729: 1 }], @@ -79,32 +86,26 @@ FINGERPRINTS = { 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 450: 8, 464: 8, 470: 2, 476: 7, 487: 4, 490: 8, 493: 5, 506: 8, 512: 6, 513: 6, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1633: 8, }], CAR.CIVIC_BOSCH: [{ - # 2017 Civic Hatchback EX, 2019 Civic Sedan Touring Canadian, and 2018 Civic Hatchback Executive Premium 1.0L CVT European 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 460: 3, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1625: 5, 1629: 5, 1633: 8, }, - # 2017 Civic Hatchback LX { 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 815: 8, 825: 4, 829: 5, 846: 8, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 892: 8, 918: 7, 927: 8, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1092: 1, 1108: 8, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1633: 8 }], CAR.CRV_5G: [{ 57: 3, 148: 8, 199: 4, 228: 5, 231: 5, 232: 7, 304: 8, 330: 8, 340: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 467: 2, 469: 3, 470: 2, 474: 8, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 507: 1, 545: 6, 597: 8, 661: 4, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 814: 4, 815: 8, 817: 4, 825: 4, 829: 5, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 927: 8, 918: 7, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1108: 8, 1092: 1, 1115: 2, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1618: 5, 1633: 8, 1670: 5 }], - # 2018 Odyssey w/ Added Comma Pedal Support (512L & 513L) CAR.ODYSSEY: [{ 57: 3, 148: 8, 228: 5, 229: 4, 316: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1619: 5, 1623: 5, 1668: 5 }, - # 2018 Odyssey Elite w/ Added Comma Pedal Support (512L & 513L) { 57: 3, 148: 8, 228: 5, 229: 4, 304: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 440: 8, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1616: 5, 1619: 5, 1623: 5, 1668: 5 }], CAR.ODYSSEY_CHN: [{ 57: 3, 145: 8, 316: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 7, 401: 8, 404: 4, 411: 5, 420: 8, 422: 8, 423: 2, 426: 8, 432: 7, 450: 8, 464: 8, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 597: 8, 610: 8, 611: 8, 612: 8, 617: 8, 660: 8, 661: 4, 773: 7, 780: 8, 804: 8, 808: 8, 829: 5, 862: 8, 884: 7, 892: 8, 923: 2, 929: 8, 1030: 5, 1137: 8, 1302: 8, 1348: 5, 1361: 5, 1365: 5, 1600: 5, 1601: 8, 1639: 8 }], - # this fingerprint also includes the Passport 2019 CAR.PILOT_2019: [{ 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 }, - # 2019 Pilot EX-L { 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 }], @@ -204,6 +205,7 @@ FW_VERSIONS = { b'77959-TBX-H230\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TVC-C010\x00\x00', b'78109-TVA-A210\x00\x00', b'78109-TVC-A010\x00\x00', b'78109-TVC-A020\x00\x00', @@ -287,12 +289,10 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TWA-A080\x00\x00', b'36802-TWA-A070\x00\x00', - b'36802-TWA-A330\x00\x00', ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TVA-A160\x00\x00', @@ -300,6 +300,78 @@ FW_VERSIONS = { b'39990-TVA-A340\x00\x00', ], }, + CAR.ACCORD_2021: { + (Ecu.programmedFuelInjection, 0x18da10f1, None): [ + b'37805-6B2-C520\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28102-6B8-A700\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TVA-A320\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TVA-A020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-E520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TVA-L420\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TVC-A230\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A110\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TVC-A910\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TVC-A330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TVC-A330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA-A340\x00\x00', + ], + (Ecu.unknown, 0x18da3af1, None): [ + b'39390-TVA-A120\x00\x00', + ], + }, + CAR.ACCORDH_2021: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TWD-J020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TWA-A530\x00\x00', + b'57114-TWA-B520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TWA-L420\x00\x00', + ], + (Ecu.combinationMeter, 0x18da60f1, None): [ + b'78109-TWA-A030\x00\x00', + b'78109-TWA-A230\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TWA-A330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TWA-A330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TVA-A340\x00\x00', + ], + (Ecu.unknown, 0x18da3af1, None): [ + b'39390-TVA-A120\x00\x00', + ], + }, CAR.CIVIC: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ b'37805-5AA-A640\x00\x00', @@ -314,6 +386,7 @@ FW_VERSIONS = { b'37805-5AA-L660\x00\x00', b'37805-5AA-L680\x00\x00', b'37805-5AA-L690\x00\x00', + b'37805-5AA-L810\000\000', b'37805-5AG-Q710\x00\x00', b'37805-5AJ-A610\x00\x00', b'37805-5AJ-A620\x00\x00', @@ -336,12 +409,12 @@ FW_VERSIONS = { 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', - b'28101-5CG-A320\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ b'57114-TBA-A540\x00\x00', @@ -354,8 +427,8 @@ FW_VERSIONS = { b'39990-TBA,A030\x00\x00', # modified firmware b'39990-TBA-A030\x00\x00', b'39990-TBG-A030\x00\x00', - b'39990-TEG-A010\x00\x00', b'39990-TEA-T020\x00\x00', + b'39990-TEG-A010\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ b'77959-TBA-A030\x00\x00', @@ -387,9 +460,9 @@ FW_VERSIONS = { 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', - b'36161-TED-Q320\x00\x00', ], (Ecu.gateway, 0x18daeff1, None): [ b'38897-TBA-A010\x00\x00', @@ -1228,7 +1301,9 @@ FW_VERSIONS = { DBC = { CAR.ACCORD: dbc_dict('honda_accord_2018_can_generated', None), + CAR.ACCORD_2021: dbc_dict('honda_accord_2018_can_generated', None), CAR.ACCORDH: dbc_dict('honda_accord_2018_can_generated', None), + CAR.ACCORDH_2021: dbc_dict('honda_accord_2018_can_generated', None), CAR.ACURA_ILX: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.ACURA_RDX: dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.ACURA_RDX_3G: dbc_dict('acura_rdx_2020_can_generated', None), @@ -1250,50 +1325,24 @@ DBC = { } STEER_THRESHOLD = { - CAR.ACCORD: 1200, - CAR.ACCORDH: 1200, - CAR.ACURA_ILX: 1200, + # default is 1200, overrides go here CAR.ACURA_RDX: 400, - CAR.ACURA_RDX_3G: 1200, - CAR.CIVIC: 1200, - CAR.CIVIC_BOSCH: 1200, - CAR.CIVIC_BOSCH_DIESEL: 1200, - CAR.CRV: 1200, - CAR.CRV_5G: 1200, CAR.CRV_EU: 400, - CAR.CRV_HYBRID: 1200, - CAR.FIT: 1200, - CAR.HRV: 1200, - CAR.ODYSSEY: 1200, - CAR.ODYSSEY_CHN: 1200, - CAR.PILOT: 1200, - CAR.PILOT_2019: 1200, - CAR.RIDGELINE: 1200, - CAR.INSIGHT: 1200, } +# TODO: is this real? SPEED_FACTOR = { - CAR.ACCORD: 1., - CAR.ACCORDH: 1., - CAR.ACURA_ILX: 1., - CAR.ACURA_RDX: 1., - CAR.ACURA_RDX_3G: 1., - CAR.CIVIC: 1., - CAR.CIVIC_BOSCH: 1., - CAR.CIVIC_BOSCH_DIESEL: 1., + # default is 1, overrides go here CAR.CRV: 1.025, CAR.CRV_5G: 1.025, CAR.CRV_EU: 1.025, CAR.CRV_HYBRID: 1.025, - CAR.FIT: 1., CAR.HRV: 1.025, - CAR.ODYSSEY: 1., - CAR.ODYSSEY_CHN: 1., - CAR.PILOT: 1., - CAR.PILOT_2019: 1., - CAR.RIDGELINE: 1., - CAR.INSIGHT: 1., } -HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G]) -HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G]) +OLD_NIDEC_LONG_CONTROL = set([CAR.ODYSSEY, CAR.ACURA_RDX, CAR.CRV, CAR.HRV]) +HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORD_2021, CAR.ACCORDH, CAR.ACCORDH_2021, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G]) +HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.ACCORD_2021, CAR.CRV_5G, CAR.ACURA_RDX_3G]) + +# Bosch models with alternate set of LKAS_HUD messages +HONDA_BOSCH_EXT = set([CAR.ACCORD_2021, CAR.ACCORDH_2021]) diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 2bfc40425..026b2dada 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -77,8 +77,9 @@ class CarController(): self.last_resume_frame = frame # 20 Hz LFA MFA message - if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KONA_EV, - CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: + if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, + CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.KONA_EV, + CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV]: can_sends.append(create_lfahda_mfc(self.packer, enabled)) return can_sends diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 56ae8e409..167e1597e 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -17,7 +17,9 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_ActToi"] = steer_req values["CF_Lkas_MsgCount"] = frame % 0x10 - if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.SANTA_FE, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: + if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE, + CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021, + CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV]: values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) values["CF_Lkas_LdwsOpt_USM"] = 2 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 9edb1bdbf..c09e1872d 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -38,7 +38,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] - elif candidate == CAR.SONATA: + elif candidate in [CAR.SONATA, CAR.SONATA_HYBRID]: ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 @@ -57,7 +57,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1999. + STD_CARGO_KG ret.wheelbase = 2.90 - ret.steerRatio = 13.75 * 1.15 + ret.steerRatio = 15.6 * 1.15 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]] elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]: @@ -100,22 +100,14 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] ret.lateralTuning.indi.actuatorEffectivenessV = [2.3] ret.minSteerSpeed = 60 * CV.KPH_TO_MS - elif candidate == CAR.KONA: + elif candidate in [CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV]: ret.lateralTuning.pid.kf = 0.00005 - ret.mass = 1275. + STD_CARGO_KG + ret.mass = {CAR.KONA_EV: 1685., CAR.KONA_HEV: 1425.}.get(candidate, 1275.) + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 13.73 * 1.15 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate == CAR.KONA_EV: - ret.lateralTuning.pid.kf = 0.00006 - ret.mass = 1685. + STD_CARGO_KG - ret.wheelbase = 2.7 - ret.steerRatio = 13.73 # Spec - tire_stiffness_factor = 0.385 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV]: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx @@ -143,11 +135,11 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate in [CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV]: + elif candidate in [CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021]: ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 - ret.steerRatio = 13.73 # Spec + ret.steerRatio = 13.9 if CAR.KIA_NIRO_HEV_2021 else 13.73 # Spec tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index f3fed2b19..33b08fb49 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -7,7 +7,9 @@ Ecu = car.CarParams.Ecu # Steer torque limits class CarControllerParams: def __init__(self, CP): - if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021]: + if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, + CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, + CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV]: self.STEER_MAX = 384 else: self.STEER_MAX = 255 @@ -31,16 +33,19 @@ class CAR: IONIQ_PHEV = "HYUNDAI IONIQ PHEV 2020" KONA = "HYUNDAI KONA 2020" KONA_EV = "HYUNDAI KONA ELECTRIC 2019" + KONA_HEV = "HYUNDAI KONA HYBRID 2020" SANTA_FE = "HYUNDAI SANTA FE 2019" SONATA = "HYUNDAI SONATA 2020" SONATA_LF = "HYUNDAI SONATA 2019" PALISADE = "HYUNDAI PALISADE 2020" VELOSTER = "HYUNDAI VELOSTER 2019" + SONATA_HYBRID = "HYUNDAI SONATA HYBRID 2021" # Kia KIA_FORTE = "KIA FORTE E 2018 & GT 2021" KIA_NIRO_EV = "KIA NIRO EV 2020" KIA_NIRO_HEV = "KIA NIRO HYBRID 2019" + KIA_NIRO_HEV_2021 = "KIA NIRO HYBRID 2021" KIA_OPTIMA = "KIA OPTIMA SX 2019 & 2016" KIA_OPTIMA_H = "KIA OPTIMA HYBRID 2017 & SPORTS 2019" KIA_SELTOS = "KIA SELTOS 2021" @@ -581,6 +586,24 @@ FW_VERSIONS = { b'\xf1\000DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', ], }, + CAR.KIA_NIRO_HEV_2021: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6G5051\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\x00\x00\x00\x00', + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HDE0G16NL3\xb9\xd3\xfaW', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + ], + }, CAR.KIA_SELTOS: { (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x8799110Q5100\xf1\000SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 \xf1\xa01.05',], (Ecu.esp, 0x7d1, None): [ @@ -647,16 +670,44 @@ FW_VERSIONS = { b'\xf1\x8756310/BY050\xf1\000CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102\xf1\xa01.02' ], (Ecu.transmission, 0x7e1, None) :[ - b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa' + b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\xb9?A\xaa', + b'\xf1\x816U3K3051\000\000\xf1\0006U3L0_C2\000\0006U3K3051\000\000HCN0G16NS0\000\000\000\000' ], (Ecu.engine, 0x7e0, None) : [ b'\xf1\x816H6G5051\000\000\000\000\000\000\000\000' ] - } + }, + CAR.KONA_HEV: { + (Ecu.esp, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000\xf1\xa01.04', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 \xf1\xa01.01', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x816U3J9051\x00\x00\xf1\x006U3H1_C2\x00\x006U3J9051\x00\x00HOS0G16DS1\x16\xc7\xb0\xd9', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x816H6F6051\x00\x00\x00\x00\x00\x00\x00\x00', + ] + }, + CAR.SONATA_HYBRID: { + (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\000DNhe SCC FHCUP 1.00 1.02 99110-L5000 ',], + (Ecu.eps, 0x7d4, None): [b'\xf1\x8756310-L5500\xf1\000DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102\xf1\xa01.02',], + (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\000DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016',], + (Ecu.transmission, 0x7e1, None): [b'\xf1\000PSBG2323 E09\000\000\000\000\000\000\000TDN2H20SA5\x97R\x88\x9e',], + (Ecu.engine, 0x7e0, None): [b'\xf1\x87391162J012\xf1\xa0000R',], + }, } CHECKSUM = { - "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021], + "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID], "6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS], } @@ -664,13 +715,13 @@ FEATURES = { # which message has the gear "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA]), "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER]), - "use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021]), + "use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021,CAR.SONATA_HYBRID, CAR.KONA_HEV]), # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS]), + "use_fca": set([CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV]), } -HYBRID_CAR = set([CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV]) # these cars use a different gas signal +HYBRID_CAR = set([CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV]) # these cars use a different gas signal EV_CAR = set([CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_NIRO_EV]) DBC = { @@ -689,6 +740,7 @@ DBC = { CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', None), CAR.KIA_NIRO_HEV: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA_H: dbc_dict('hyundai_kia_generic', None), CAR.KIA_SELTOS: dbc_dict('hyundai_kia_generic', None), @@ -696,12 +748,14 @@ DBC = { CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None), CAR.KONA: dbc_dict('hyundai_kia_generic', None), CAR.KONA_EV: dbc_dict('hyundai_kia_generic', None), + CAR.KONA_HEV: dbc_dict('hyundai_kia_generic', None), CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None), CAR.SONATA: dbc_dict('hyundai_kia_generic', None), CAR.SONATA_LF: dbc_dict('hyundai_kia_generic', None), CAR.PALISADE: dbc_dict('hyundai_kia_generic', None), CAR.VELOSTER: dbc_dict('hyundai_kia_generic', None), CAR.KIA_CEED: dbc_dict('hyundai_kia_generic', None), + CAR.SONATA_HYBRID: dbc_dict('hyundai_kia_generic', None), } STEER_THRESHOLD = 150 diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 7699a62a1..a9d26164d 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -619,6 +619,7 @@ FW_VERSIONS = { b'\x01896630ZP2000\x00\x00\x00\x00', b'\x01896630ZQ5000\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', @@ -630,6 +631,7 @@ FW_VERSIONS = { b'\x018966312R3100\x00\x00\x00\x00', b'\x018966312S5000\x00\x00\x00\x00', b'\x018966312S7000\x00\x00\x00\x00', + b'\x018966312W3000\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', @@ -690,10 +692,12 @@ FW_VERSIONS = { b'\x01896637624000\x00\x00\x00\x00', b'\x01896637626000\x00\x00\x00\x00', b'\x01896637648000\x00\x00\x00\x00', + b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', 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'\x028966312Q3000\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', @@ -716,6 +720,7 @@ FW_VERSIONS = { 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', @@ -851,6 +856,7 @@ FW_VERSIONS = { b'\x01F152648C6300\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ + b'\x01896630EA1000\000\000\000\000', b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', @@ -1418,6 +1424,7 @@ FW_VERSIONS = { b'\x01896630E41000\x00\x00\x00\x00', b'\x01896630E41100\x00\x00\x00\x00', b'\x01896630E41200\x00\x00\x00\x00', + b'\x01896630EA3100\x00\x00\x00\x00', b'\x01896630EA4100\x00\x00\x00\x00', b'\x01896630EA4300\x00\x00\x00\x00', b'\x01896630EA6300\x00\x00\x00\x00', diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 63cd8d291..6de77db52 100644 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -438,6 +438,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704L906021EL\xf1\x897542', b'\xf1\x8704L906026BP\xf1\x891198', + b'\xf1\x8704L906026BP\xf1\x897608', b'\xf1\x8705E906018AS\xf1\x899596', ], (Ecu.transmission, 0x7e1, None): [ @@ -488,12 +489,14 @@ FW_VERSIONS = { CAR.SKODA_OCTAVIA_MK3: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906016ER\xf1\x895823', b'\xf1\x8704L906021DT\xf1\x898127', b'\xf1\x8704L906026BS\xf1\x891541', b'\xf1\x875G0906259C \xf1\x890002', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300041N \xf1\x891605', b'\xf1\x870D9300041C \xf1\x894936', b'\xf1\x870D9300041J \xf1\x894902', b'\xf1\x870D9300041P \xf1\x894507', @@ -502,16 +505,19 @@ FW_VERSIONS = { b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\0163221003221002105755331052100', b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', ], (Ecu.eps, 0x712, None): [ b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\00566A01513A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\00521T00403A1', b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\00101', + b'\xf1\x875Q0907572J \xf1\x890654', b'\xf1\x875Q0907572P \xf1\x890682', ], }, @@ -537,10 +543,12 @@ FW_VERSIONS = { b'\xf1\x8704L906026KB\xf1\x894071', b'\xf1\x873G0906259B \xf1\x890002', b'\xf1\x8704L906026FP\xf1\x891196', + b'\xf1\x873G0906264A \xf1\x890002', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x870D9300012 \xf1\x894940', b'\xf1\x870D9300011T \xf1\x894801', + b'\xf1\x870CW300042H \xf1\x891601', ], (Ecu.srs, 0x715, None): [ b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111', @@ -551,6 +559,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\00563UZ060700', b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x873Q0907572B \xf1\x890194', diff --git a/selfdrive/clocksd/clocksd.cc b/selfdrive/clocksd/clocksd.cc index 951a92467..c24ffa41d 100644 --- a/selfdrive/clocksd/clocksd.cc +++ b/selfdrive/clocksd/clocksd.cc @@ -50,7 +50,10 @@ int main() { uint64_t expirations = 0; while (!do_exit && (err = read(timerfd, &expirations, sizeof(expirations)))) { - if (err < 0) break; + if (err < 0) { + if (errno == EINTR) continue; + break; + } #else // Just run at 1Hz on apple while (!do_exit) { diff --git a/selfdrive/common/clutil.cc b/selfdrive/common/clutil.cc index 68207c286..952fc6863 100644 --- a/selfdrive/common/clutil.cc +++ b/selfdrive/common/clutil.cc @@ -88,7 +88,7 @@ cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const ch return prg; } -// Given a cl code and return a string represenation +// Given a cl code and return a string representation #define CL_ERR_TO_STR(err) case err: return #err const char* cl_get_error_string(int err) { switch (err) { diff --git a/selfdrive/common/clutil.h b/selfdrive/common/clutil.h index 4c8723d64..ffddafadb 100644 --- a/selfdrive/common/clutil.h +++ b/selfdrive/common/clutil.h @@ -11,7 +11,7 @@ #define CL_CHECK(_expr) \ do { \ - assert(CL_SUCCESS == _expr); \ + assert(CL_SUCCESS == (_expr)); \ } while (0) #define CL_CHECK_ERR(_expr) \ diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 4eb306805..49e200d54 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -1,7 +1,7 @@ #pragma once const int TRAJECTORY_SIZE = 33; -const int LON_MPC_N = 32; const int LAT_MPC_N = 16; +const int LON_MPC_N = 32; const float MIN_DRAW_DISTANCE = 10.0; const float MAX_DRAW_DISTANCE = 100.0; diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index ad5121893..cada3b8ad 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -33,10 +33,6 @@ namespace { -const std::string default_params_path = Hardware::PC() ? util::getenv_default("HOME", "/.comma/params", "/data/params") - : "/data/params"; -const std::string persistent_params_path = Hardware::PC() ? default_params_path : "/persist/comma/params"; - volatile sig_atomic_t params_do_exit = 0; void params_sig_handler(int signal) { params_do_exit = 1; @@ -78,7 +74,7 @@ int mkdir_p(std::string path) { return 0; } -static bool create_params_path(const std::string ¶m_path, const std::string &key_path) { +bool create_params_path(const std::string ¶m_path, const std::string &key_path) { // Make sure params path exists if (!util::file_exists(param_path) && mkdir_p(param_path) != 0) { return false; @@ -117,7 +113,7 @@ static bool create_params_path(const std::string ¶m_path, const std::string return chmod(key_path.c_str(), 0777) == 0; } -static void ensure_params_path(const std::string ¶ms_path) { +void ensure_params_path(const std::string ¶ms_path) { if (!create_params_path(params_path, params_path + "/d")) { throw std::runtime_error(util::string_format("Failed to ensure params path, errno=%d", errno)); } @@ -198,6 +194,7 @@ std::unordered_map keys = { {"PandaFirmware", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, {"PandaFirmwareHex", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, {"PandaDongleId", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, + {"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"Passive", PERSISTENT}, {"PrimeRedirected", PERSISTENT}, {"RecordFront", PERSISTENT}, @@ -231,15 +228,13 @@ std::unordered_map keys = { } // namespace -Params::Params(bool persistent_param) : Params(persistent_param ? persistent_params_path : default_params_path) {} +Params::Params() : params_path(Path::params()) { + static std::once_flag once_flag; + std::call_once(once_flag, ensure_params_path, params_path); +} -std::once_flag default_params_path_ensured; Params::Params(const std::string &path) : params_path(path) { - if (path == default_params_path) { - std::call_once(default_params_path_ensured, ensure_params_path, path); - } else { - ensure_params_path(path); - } + ensure_params_path(params_path); } bool Params::checkKey(const std::string &key) { @@ -331,12 +326,12 @@ std::string Params::get(const char *key, bool block) { } } -int Params::readAll(std::map *params) { +std::map Params::readAll() { FileLock file_lock(params_path + "/.lock", LOCK_SH); std::lock_guard lk(file_lock); std::string key_path = params_path + "/d"; - return util::read_files_in_dir(key_path, params); + return util::read_files_in_dir(key_path); } void Params::clearAll(ParamKeyType key_type) { diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index a85a73b0a..3c9d99895 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -13,15 +13,12 @@ enum ParamKeyType { CLEAR_ON_IGNITION_ON = 0x10, CLEAR_ON_IGNITION_OFF = 0x20, DONT_LOG = 0x40, - ALL = 0x02 | 0x04 | 0x08 | 0x10 | 0x20 | 0x40 + ALL = 0xFFFFFFFF }; class Params { -private: - std::string params_path; - public: - Params(bool persistent_param = false); + Params(); Params(const std::string &path); bool checkKey(const std::string &key); @@ -35,7 +32,7 @@ public: void clearAll(ParamKeyType type); // read all values - int readAll(std::map *params); + std::map readAll(); // helpers for reading values std::string get(const char *key, bool block = false); @@ -78,4 +75,7 @@ public: inline int putBool(const std::string &key, bool val) { return putBool(key.c_str(), val); } + +private: + const std::string params_path; }; diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h index fae44152d..9a1d3c0a6 100644 --- a/selfdrive/common/swaglog.h +++ b/selfdrive/common/swaglog.h @@ -31,7 +31,7 @@ void cloudlog_bind(const char* k, const char* v); \ if (__begin + __millis*1000000ULL < __ts) { \ if (__missed) { \ - cloudlog(CLOUDLOG_WARNING, "cloudlog: %d messages supressed", __missed); \ + cloudlog(CLOUDLOG_WARNING, "cloudlog: %d messages suppressed", __missed); \ } \ __begin = 0; \ __printed = 0; \ diff --git a/selfdrive/common/util.cc b/selfdrive/common/util.cc index 78f9e409f..cf570430e 100644 --- a/selfdrive/common/util.cc +++ b/selfdrive/common/util.cc @@ -1,5 +1,7 @@ #include "selfdrive/common/util.h" +#include + #include #include #include @@ -76,19 +78,20 @@ std::string read_file(const std::string& fn) { return std::string(); } -int read_files_in_dir(const std::string &path, std::map *contents) { +std::map read_files_in_dir(const std::string &path) { + std::map ret; DIR *d = opendir(path.c_str()); - if (!d) return -1; + if (!d) return ret; struct dirent *de = NULL; while ((de = readdir(d))) { if (isalnum(de->d_name[0])) { - (*contents)[de->d_name] = util::read_file(path + "/" + de->d_name); + ret[de->d_name] = util::read_file(path + "/" + de->d_name); } } closedir(d); - return 0; + return ret; } int write_file(const char* path, const void* data, size_t size, int flags, mode_t mode) { @@ -112,17 +115,23 @@ std::string readlink(const std::string &path) { } bool file_exists(const std::string& fn) { - std::ifstream f(fn); - return f.good(); + struct stat st = {}; + return stat(fn.c_str(), &st) != -1; } -std::string getenv_default(const char* env_var, const char * suffix, const char* default_val) { - const char* env_val = getenv(env_var); - if (env_val != NULL) { - return std::string(env_val) + std::string(suffix); - } else { - return std::string(default_val); - } +std::string getenv(const char* key, const char* default_val) { + const char* val = ::getenv(key); + return val ? val : default_val; +} + +int getenv(const char* key, int default_val) { + const char* val = ::getenv(key); + return val ? atoi(val) : default_val; +} + +float getenv(const char* key, float default_val) { + const char* val = ::getenv(key); + return val ? atof(val) : default_val; } std::string tohex(const uint8_t *buf, size_t buf_size) { @@ -155,10 +164,6 @@ std::string dir_name(std::string const &path) { return path.substr(0, pos); } -bool is_valid_dongle_id(std::string const& dongle_id) { - return !dongle_id.empty() && dongle_id != "UnregisteredDevice"; -} - struct tm get_time() { time_t rawtime; time(&rawtime); diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 460fb8f5c..845e71614 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -41,10 +41,6 @@ T map_val(T x, T a1, T a2, T b1, T b2) { // ***** string helpers ***** -inline bool starts_with(const std::string& s, const std::string& prefix) { - return s.compare(0, prefix.size(), prefix) == 0; -} - template std::string string_format(const std::string& format, Args... args) { size_t size = snprintf(nullptr, 0, format.c_str(), args...) + 1; @@ -53,16 +49,18 @@ std::string string_format(const std::string& format, Args... args) { return std::string(buf.get(), buf.get() + size - 1); } -std::string getenv_default(const char* env_var, const char* suffix, const char* default_val); +std::string getenv(const char* key, const char* default_val = ""); +int getenv(const char* key, int default_val); +float getenv(const char* key, float default_val); + std::string tohex(const uint8_t* buf, size_t buf_size); std::string hexdump(const std::string& in); std::string base_name(std::string const& path); std::string dir_name(std::string const& path); -bool is_valid_dongle_id(std::string const& dongle_id); // **** file fhelpers ***** std::string read_file(const std::string& fn); -int read_files_in_dir(const std::string& path, std::map* contents); +std::map read_files_in_dir(const std::string& path); int write_file(const char* path, const void* data, size_t size, int flags = O_WRONLY, mode_t mode = 0777); std::string readlink(const std::string& path); bool file_exists(const std::string& fn); diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index 617206a18..0ca772f90 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.7" +#define COMMA_VERSION "0.8.8" diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index a56ac18a5..6cd5060b1 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -23,7 +23,8 @@ from selfdrive.controls.lib.events import Events, ET from selfdrive.controls.lib.alertmanager import AlertManager from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.locationd.calibrationd import Calibration -from selfdrive.hardware import HARDWARE, TICI +from selfdrive.hardware import HARDWARE, TICI, EON +from selfdrive.manager.process_config import managed_processes LDW_MIN_SPEED = 31 * CV.MPH_TO_MS LANE_DEPARTURE_THRESHOLD = 0.1 @@ -32,7 +33,11 @@ STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees SIMULATION = "SIMULATION" in os.environ NOSENSOR = "NOSENSOR" in os.environ -IGNORE_PROCESSES = set(["rtshield", "uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"]) +IGNORE_PROCESSES = {"rtshield", "uploader", "deleter", "loggerd", "logmessaged", "tombstoned", + "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \ + {k for k, v in managed_processes.items() if not v.enabled} + +ACTUATOR_FIELDS = set(car.CarControl.Actuators.schema.fields.keys()) ThermalStatus = log.DeviceState.ThermalStatus State = log.ControlsState.OpenpilotState @@ -196,6 +201,9 @@ class Controls: # TODO: make tici threshold the same if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65) and not SIMULATION: self.events.add(EventName.lowMemory) + cpus = list(self.sm['deviceState'].cpuUsagePercent)[:(-1 if EON else None)] + if max(cpus, default=0) > 95: + self.events.add(EventName.highCpuUsage) # Alert if fan isn't spinning for 5 seconds if self.sm['pandaState'].pandaType in [PandaType.uno, PandaType.dos]: @@ -497,6 +505,12 @@ class Controls: if left_deviation or right_deviation: self.events.add(EventName.steerSaturated) + # Ensure no NaNs/Infs + for p in ACTUATOR_FIELDS: + if not math.isfinite(getattr(actuators, p)): + cloudlog.error(f"actuators.{p} not finite {actuators.to_dict()}") + setattr(actuators, p, 0.0) + return actuators, lac_log def publish_logs(self, CS, start_time, actuators, lac_log): diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index c7af80333..6a02ff23e 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -240,6 +240,8 @@ def joystick_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool) -> EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, bool], Alert]]]] = { # ********** events with no alerts ********** + EventName.stockFcw: {}, + # ********** events only containing alerts displayed in all states ********** EventName.joystickDebug: { @@ -357,15 +359,6 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo ET.NO_ENTRY: NoEntryAlert("Stock AEB: Risk of Collision"), }, - EventName.stockFcw: { - ET.PERMANENT: Alert( - "BRAKE!", - "Stock FCW: Risk of Collision", - AlertStatus.critical, AlertSize.full, - Priority.HIGHEST, VisualAlert.fcw, AudibleAlert.none, 1., 2., 2.), - ET.NO_ENTRY: NoEntryAlert("Stock FCW: Risk of Collision"), - }, - EventName.fcw: { ET.PERMANENT: Alert( "BRAKE!", @@ -423,7 +416,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo "KEEP EYES ON ROAD: Driver Distracted", "", AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1), + Priority.LOW, VisualAlert.none, AudibleAlert.none, .0, .1, .1), }, EventName.promptDriverDistracted: { @@ -488,34 +481,34 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo EventName.preLaneChangeLeft: { ET.WARNING: Alert( - "Steer Left to Start Lane Change", - "Monitor Other Vehicles", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + "Steer Left to Start Lane Change Once Safe", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), }, EventName.preLaneChangeRight: { ET.WARNING: Alert( - "Steer Right to Start Lane Change", - "Monitor Other Vehicles", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + "Steer Right to Start Lane Change Once Safe", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), }, EventName.laneChangeBlocked: { ET.WARNING: Alert( "Car Detected in Blindspot", - "Monitor Other Vehicles", - AlertStatus.userPrompt, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, .1, .1, .1), + "", + AlertStatus.userPrompt, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.chimePrompt, .1, .1, .1), }, EventName.laneChange: { ET.WARNING: Alert( - "Changing Lane", - "Monitor Other Vehicles", - AlertStatus.normal, AlertSize.mid, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1), + "Changing Lanes", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .0, .1, .1), }, EventName.steerSaturated: { @@ -736,7 +729,14 @@ EVENTS: Dict[int, Dict[str, Union[Alert, Callable[[Any, messaging.SubMaster, boo ET.SOFT_DISABLE: SoftDisableAlert("Low Memory: Reboot Your Device"), ET.PERMANENT: NormalPermanentAlert("Low Memory", "Reboot your Device"), ET.NO_ENTRY: NoEntryAlert("Low Memory: Reboot Your Device", - audible_alert=AudibleAlert.chimeDisengage), + audible_alert=AudibleAlert.chimeDisengage), + }, + + EventName.highCpuUsage: { + #ET.SOFT_DISABLE: SoftDisableAlert("System Malfunction: Reboot Your Device"), + #ET.PERMANENT: NormalPermanentAlert("System Malfunction", "Reboot your Device"), + ET.NO_ENTRY: NoEntryAlert("System Malfunction: Reboot Your Device", + audible_alert=AudibleAlert.chimeDisengage), }, EventName.accFaulted: { diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py index 0c55e101d..88a1f6a67 100644 --- a/selfdrive/controls/lib/lane_planner.py +++ b/selfdrive/controls/lib/lane_planner.py @@ -1,8 +1,10 @@ -from common.numpy_fast import interp import numpy as np +from cereal import log +from common.filter_simple import FirstOrderFilter +from common.numpy_fast import interp +from common.realtime import DT_MDL from selfdrive.hardware import EON, TICI from selfdrive.swaglog import cloudlog -from cereal import log TRAJECTORY_SIZE = 33 @@ -24,8 +26,8 @@ class LanePlanner: self.ll_x = np.zeros((TRAJECTORY_SIZE,)) self.lll_y = np.zeros((TRAJECTORY_SIZE,)) self.rll_y = np.zeros((TRAJECTORY_SIZE,)) - self.lane_width_estimate = 3.7 - self.lane_width_certainty = 1.0 + self.lane_width_estimate = FirstOrderFilter(3.7, 9.95, DT_MDL) + self.lane_width_certainty = FirstOrderFilter(1.0, 0.95, DT_MDL) self.lane_width = 3.7 self.lll_prob = 0. @@ -79,12 +81,12 @@ class LanePlanner: r_prob *= r_std_mod # Find current lanewidth - self.lane_width_certainty += 0.05 * (l_prob * r_prob - self.lane_width_certainty) + self.lane_width_certainty.update(l_prob * r_prob) current_lane_width = abs(self.rll_y[0] - self.lll_y[0]) - self.lane_width_estimate += 0.005 * (current_lane_width - self.lane_width_estimate) + self.lane_width_estimate.update(current_lane_width) speed_lane_width = interp(v_ego, [0., 31.], [2.8, 3.5]) - self.lane_width = self.lane_width_certainty * self.lane_width_estimate + \ - (1 - self.lane_width_certainty) * speed_lane_width + self.lane_width = self.lane_width_certainty.x * self.lane_width_estimate.x + \ + (1 - self.lane_width_certainty.x) * speed_lane_width clipped_lane_width = min(4.0, self.lane_width) path_from_left_lane = self.lll_y + clipped_lane_width / 2.0 diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index 6f234efde..cee391d45 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -2,10 +2,11 @@ import math import numpy as np from cereal import log -from common.realtime import DT_CTRL +from common.filter_simple import FirstOrderFilter from common.numpy_fast import clip, interp -from selfdrive.car.toyota.values import CarControllerParams +from common.realtime import DT_CTRL from selfdrive.car import apply_toyota_steer_torque_limits +from selfdrive.car.toyota.values import CarControllerParams from selfdrive.controls.lib.drive_helpers import get_steer_max @@ -43,6 +44,7 @@ class LatControlINDI(): self.sat_count_rate = 1.0 * DT_CTRL self.sat_limit = CP.steerLimitTimer + self.steer_filter = FirstOrderFilter(0., self.RC, DT_CTRL) self.reset() @@ -63,9 +65,9 @@ class LatControlINDI(): return interp(self.speed, self._inner_loop_gain[0], self._inner_loop_gain[1]) def reset(self): - self.delayed_output = 0. + self.steer_filter.x = 0. self.output_steer = 0. - self.sat_count = 0.0 + self.sat_count = 0. self.speed = 0. def _check_saturation(self, control, check_saturation, limit): @@ -96,14 +98,14 @@ class LatControlINDI(): if CS.vEgo < 0.3 or not active: indi_log.active = False self.output_steer = 0.0 - self.delayed_output = 0.0 + self.steer_filter.x = 0.0 else: rate_des = VM.get_steer_from_curvature(-curvature_rate, CS.vEgo) # Expected actuator value - alpha = 1. - DT_CTRL / (self.RC + DT_CTRL) - self.delayed_output = self.delayed_output * alpha + self.output_steer * (1. - alpha) + self.steer_filter.update_alpha(self.RC) + self.steer_filter.update(self.output_steer) # Compute acceleration error rate_sp = self.outer_loop_gain * (steers_des - self.x[0]) + rate_des @@ -121,12 +123,12 @@ class LatControlINDI(): # Enforce rate limit if self.enforce_rate_limit: steer_max = float(CarControllerParams.STEER_MAX) - new_output_steer_cmd = steer_max * (self.delayed_output + delta_u) + new_output_steer_cmd = steer_max * (self.steer_filter.x + delta_u) prev_output_steer_cmd = steer_max * self.output_steer new_output_steer_cmd = apply_toyota_steer_torque_limits(new_output_steer_cmd, prev_output_steer_cmd, prev_output_steer_cmd, CarControllerParams) self.output_steer = new_output_steer_cmd / steer_max else: - self.output_steer = self.delayed_output + delta_u + self.output_steer = self.steer_filter.x + delta_u steers_max = get_steer_max(CP, CS.vEgo) self.output_steer = clip(self.output_steer, -steers_max, steers_max) @@ -135,7 +137,7 @@ class LatControlINDI(): indi_log.rateSetPoint = float(rate_sp) indi_log.accelSetPoint = float(accel_sp) indi_log.accelError = float(accel_error) - indi_log.delayedOutput = float(self.delayed_output) + indi_log.delayedOutput = float(self.steer_filter.x) indi_log.delta = float(delta_u) indi_log.output = float(self.output_steer) diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 0c258d8db..1c3ca8989 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -55,6 +55,7 @@ class LateralPlanner(): self.lane_change_direction = LaneChangeDirection.none self.lane_change_timer = 0.0 self.lane_change_ll_prob = 1.0 + self.keep_pulse_timer = 0.0 self.prev_one_blinker = False self.desire = log.LateralPlan.Desire.none @@ -157,6 +158,16 @@ class LateralPlanner(): self.desire = DESIRES[self.lane_change_direction][self.lane_change_state] + # Send keep pulse once per second during LaneChangeStart.preLaneChange + if self.lane_change_state in [LaneChangeState.off, LaneChangeState.laneChangeStarting]: + self.keep_pulse_timer = 0.0 + elif self.lane_change_state == LaneChangeState.preLaneChange: + self.keep_pulse_timer += DT_MDL + if self.keep_pulse_timer > 1.0: + self.keep_pulse_timer = 0.0 + elif self.desire in [log.LateralPlan.Desire.keepLeft, log.LateralPlan.Desire.keepRight]: + self.desire = log.LateralPlan.Desire.none + # Turn off lanes during lane change if self.desire == log.LateralPlan.Desire.laneChangeRight or self.desire == log.LateralPlan.Desire.laneChangeLeft: self.LP.lll_prob *= self.lane_change_ll_prob diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index 6f0db25fc..4d6f3846d 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -45,12 +45,14 @@ class LongitudinalMpc(): self.cur_state[0].v_ego = v_safe self.cur_state[0].a_ego = a_safe - def update(self, carstate, model, v_cruise): + def update(self, carstate, radarstate, v_cruise): v_cruise_clipped = np.clip(v_cruise, self.cur_state[0].v_ego - 10., self.cur_state[0].v_ego + 10.0) poss = v_cruise_clipped * np.array(T_IDXS[:LON_MPC_N+1]) speeds = v_cruise_clipped * np.ones(LON_MPC_N+1) accels = np.zeros(LON_MPC_N+1) + self.update_with_xva(poss, speeds, accels) + def update_with_xva(self, poss, speeds, accels): # Calculate mpc self.libmpc.run_mpc(self.cur_state, self.mpc_solution, list(poss), list(speeds), list(accels), diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index 695615e0e..359f99266 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -72,7 +72,7 @@ class LongControl(): def update(self, active, CS, CP, long_plan): """Update longitudinal control. This updates the state machine and runs a PID loop""" # Interp control trajectory - # TODO estimate car specific lag, use .5s for now + # TODO estimate car specific lag, use .15s for now if len(long_plan.speeds) == CONTROL_N: v_target = interp(DEFAULT_LONG_LAG, T_IDXS[:CONTROL_N], long_plan.speeds) v_target_future = long_plan.speeds[-1] diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 643cefd7a..cab3e20aa 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -105,7 +105,7 @@ class Planner(): for key in self.mpcs: self.mpcs[key].set_cur_state(self.v_desired, self.a_desired) self.mpcs[key].update(sm['carState'], sm['radarState'], v_cruise) - if self.mpcs[key].status and self.mpcs[key].a_solution[5] < next_a: + if self.mpcs[key].status and self.mpcs[key].a_solution[5] < next_a: # picks slowest solution from accel in ~0.2 seconds self.longitudinalPlanSource = key self.v_desired_trajectory = self.mpcs[key].v_solution[:CONTROL_N] self.a_desired_trajectory = self.mpcs[key].a_solution[:CONTROL_N] diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index 132bba8bd..01498fa13 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -132,11 +132,11 @@ class Cluster(): def get_RadarState_from_vision(self, lead_msg, v_ego): return { - "dRel": float(lead_msg.xyva[0] - RADAR_TO_CAMERA), - "yRel": float(-lead_msg.xyva[1]), - "vRel": float(lead_msg.xyva[2]), - "vLead": float(v_ego + lead_msg.xyva[2]), - "vLeadK": float(v_ego + lead_msg.xyva[2]), + "dRel": float(lead_msg.x[0] - RADAR_TO_CAMERA), + "yRel": float(-lead_msg.y[0]), + "vRel": float(lead_msg.v[0] - v_ego), + "vLead": float(lead_msg.v[0]), + "vLeadK": float(lead_msg.v[0]), "aLeadK": float(0), "aLeadTau": _LEAD_ACCEL_TAU, "fcw": False, diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 244d02d23..5d94804d7 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -38,12 +38,12 @@ def laplacian_cdf(x, mu, b): def match_vision_to_cluster(v_ego, lead, clusters): # match vision point to best statistical cluster match - offset_vision_dist = lead.xyva[0] - RADAR_TO_CAMERA + offset_vision_dist = lead.x[0] - RADAR_TO_CAMERA def prob(c): - prob_d = laplacian_cdf(c.dRel, offset_vision_dist, lead.xyvaStd[0]) - prob_y = laplacian_cdf(c.yRel, -lead.xyva[1], lead.xyvaStd[1]) - prob_v = laplacian_cdf(c.vRel, lead.xyva[2], lead.xyvaStd[2]) + prob_d = laplacian_cdf(c.dRel, offset_vision_dist, lead.xStd[0]) + prob_y = laplacian_cdf(c.yRel, -lead.y[0], lead.yStd[0]) + prob_v = laplacian_cdf(c.vRel + v_ego, lead.v[0], lead.vStd[0]) # This is isn't exactly right, but good heuristic return prob_d * prob_y * prob_v @@ -53,7 +53,7 @@ def match_vision_to_cluster(v_ego, lead, clusters): # if no 'sane' match is found return -1 # stationary radar points can be false positives dist_sane = abs(cluster.dRel - offset_vision_dist) < max([(offset_vision_dist)*.25, 5.0]) - vel_sane = (abs(cluster.vRel - lead.xyva[2]) < 10) or (v_ego + cluster.vRel > 3) + vel_sane = (abs(cluster.vRel + v_ego - lead.v[0]) < 10) or (v_ego + cluster.vRel > 3) if dist_sane and vel_sane: return cluster else: @@ -166,9 +166,9 @@ class RadarD(): radarState.carStateMonoTime = sm.logMonoTime['carState'] if enable_lead: - if len(sm['modelV2'].leads) > 1: - radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leads[0], low_speed_override=True) - radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leads[1], low_speed_override=False) + if len(sm['modelV2'].leadsV3) > 1: + radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leadsV3[0], low_speed_override=True) + radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leadsV3[1], low_speed_override=False) return dat diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index ffff3d6ce..5931fda64 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -44,7 +44,7 @@ def get_arg_parser(): parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("proc_names", nargs="?", default='', - help="Process names to be monitored, comma seperated") + help="Process names to be monitored, comma separated") parser.add_argument("--list_all", action='store_true', help="Show all running processes' cmdline") parser.add_argument("--detailed_times", action='store_true', diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index 98e7eafec..c35791682 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -24,16 +24,13 @@ def cycle_alerts(duration=2000, is_metric=False): sm = messaging.SubMaster(['deviceState', 'pandaState', 'roadCameraState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman']) - controls_state = messaging.pub_sock('controlsState') - deviceState = messaging.pub_sock('deviceState') - - idx, last_alert_millis = 0, 0 + pm = messaging.PubMaster(['controlsState', 'pandaState', 'deviceState']) events = Events() AM = AlertManager() frame = 0 - + idx, last_alert_millis = 0, 0 while 1: if frame % duration == 0: idx = (idx + 1) % len(alerts) @@ -50,7 +47,6 @@ def cycle_alerts(duration=2000, is_metric=False): dat = messaging.new_message() dat.init('controlsState') - dat.controlsState.alertText1 = AM.alert_text_1 dat.controlsState.alertText2 = AM.alert_text_2 dat.controlsState.alertSize = AM.alert_size @@ -58,14 +54,18 @@ def cycle_alerts(duration=2000, is_metric=False): dat.controlsState.alertBlinkingRate = AM.alert_rate dat.controlsState.alertType = AM.alert_type dat.controlsState.alertSound = AM.audible_alert - controls_state.send(dat.to_bytes()) + pm.send('controlsState', dat) dat = messaging.new_message() dat.init('deviceState') dat.deviceState.started = True - deviceState.send(dat.to_bytes()) + pm.send('deviceState', dat) + + dat = messaging.new_message() + dat.init('pandaState') + dat.pandaState.ignitionLine = True + pm.send('pandaState', dat) - frame += 1 time.sleep(0.01) if __name__ == '__main__': diff --git a/selfdrive/debug/uiview.py b/selfdrive/debug/uiview.py index e194957ec..18c76c3e3 100755 --- a/selfdrive/debug/uiview.py +++ b/selfdrive/debug/uiview.py @@ -3,9 +3,8 @@ import time import cereal.messaging as messaging from selfdrive.manager.process_config import managed_processes - if __name__ == "__main__": - services = ['controlsState', 'deviceState', 'radarState'] # the services needed to be spoofed to start ui offroad + services = ['controlsState', 'deviceState', 'pandaState'] # the services needed to be spoofed to start ui offroad procs = ['camerad', 'ui', 'modeld', 'calibrationd'] for p in procs: @@ -13,15 +12,15 @@ if __name__ == "__main__": pm = messaging.PubMaster(services) - dat_controlsState, dat_deviceState, dat_radar = [messaging.new_message(s) for s in services] - dat_deviceState.deviceState.started = True + msgs = {s: messaging.new_message(s) for s in services} + msgs['deviceState'].deviceState.started = True + msgs['pandaState'].pandaState.ignitionLine = True try: while True: - pm.send('controlsState', dat_controlsState) - pm.send('deviceState', dat_deviceState) - pm.send('radarState', dat_radar) - time.sleep(1 / 100) # continually send, rate doesn't matter for deviceState + time.sleep(1 / 100) # continually send, rate doesn't matter + for s in msgs: + pm.send(s, msgs[s]) except KeyboardInterrupt: for p in procs: managed_processes[p].stop() diff --git a/selfdrive/hardware/eon/androidd.py b/selfdrive/hardware/eon/androidd.py new file mode 100755 index 000000000..6de00d8e7 --- /dev/null +++ b/selfdrive/hardware/eon/androidd.py @@ -0,0 +1,78 @@ +#!/usr/bin/env python3 +import os +import time +import psutil +from typing import Optional + +from common.realtime import set_core_affinity, set_realtime_priority +from selfdrive.swaglog import cloudlog + + +MAX_MODEM_CRASHES = 3 +MODEM_PATH = "/sys/devices/soc/2080000.qcom,mss/subsys5" +WATCHED_PROCS = ["zygote", "zygote64", "/system/bin/servicemanager", "/system/bin/surfaceflinger"] + + +def get_modem_crash_count() -> Optional[int]: + try: + with open(os.path.join(MODEM_PATH, "crash_count")) as f: + return int(f.read()) + except Exception: + cloudlog.exception("Error reading modem crash count") + return None + +def get_modem_state() -> str: + try: + with open(os.path.join(MODEM_PATH, "state")) as f: + return f.read().strip() + except Exception: + cloudlog.exception("Error reading modem state") + return "" + +def main(): + set_core_affinity(1) + set_realtime_priority(1) + + procs = {} + crash_count = 0 + modem_killed = False + modem_state = "ONLINE" + while True: + # check critical android services + if any(p is None or not p.is_running() for p in procs.values()) or not len(procs): + cur = {p: None for p in WATCHED_PROCS} + for p in psutil.process_iter(attrs=['cmdline']): + cmdline = None if not len(p.info['cmdline']) else p.info['cmdline'][0] + if cmdline in WATCHED_PROCS: + cur[cmdline] = p + + if len(procs): + for p in WATCHED_PROCS: + if cur[p] != procs[p]: + cloudlog.event("android service pid changed", proc=p, cur=cur[p], prev=procs[p]) + procs.update(cur) + + # check modem state + state = get_modem_state() + if state != modem_state and not modem_killed: + cloudlog.event("modem state changed", state=state) + modem_state = state + + # check modem crashes + cnt = get_modem_crash_count() + if cnt is not None: + if cnt > crash_count: + cloudlog.event("modem crash", count=cnt) + crash_count = cnt + + # handle excessive modem crashes + if crash_count > MAX_MODEM_CRASHES and not modem_killed: + cloudlog.event("killing modem") + with open("/sys/kernel/debug/msm_subsys/modem", "w") as f: + f.write("put") + modem_killed = True + + time.sleep(1) + +if __name__ == "__main__": + main() diff --git a/selfdrive/hardware/hw.h b/selfdrive/hardware/hw.h index 8112ba1c6..400b1816f 100644 --- a/selfdrive/hardware/hw.h +++ b/selfdrive/hardware/hw.h @@ -1,6 +1,7 @@ #pragma once #include "selfdrive/hardware/base.h" +#include "selfdrive/common/util.h" #ifdef QCOM #include "selfdrive/hardware/eon/hardware.h" @@ -16,3 +17,19 @@ public: }; #define Hardware HardwarePC #endif + +namespace Path { +inline static std::string HOME = util::getenv("HOME"); +inline std::string log_root() { + if (const char *env = getenv("LOG_ROOT")) { + return env; + } + return Hardware::PC() ? HOME + "/.comma/media/0/realdata" : "/data/media/0/realdata"; +} +inline std::string params() { + return Hardware::PC() ? HOME + "/.comma/params" : "/data/params"; +} +inline std::string rsa_file() { + return Hardware::PC() ? HOME + "/.comma/persist/comma/id_rsa" : "/persist/comma/id_rsa"; +} +} // namespace Path diff --git a/selfdrive/hardware/tici/agnos.json b/selfdrive/hardware/tici/agnos.json index 07cfb123d..1958923eb 100644 --- a/selfdrive/hardware/tici/agnos.json +++ b/selfdrive/hardware/tici/agnos.json @@ -1,10 +1,10 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-54fc7edceeabff713b51dd4d4931eb920344aa3f8f8e0f153baad1fb5a15ef19.img.xz", - "hash": "54fc7edceeabff713b51dd4d4931eb920344aa3f8f8e0f153baad1fb5a15ef19", - "hash_raw": "54fc7edceeabff713b51dd4d4931eb920344aa3f8f8e0f153baad1fb5a15ef19", - "size": 14772224, + "url": "https://commadist.azureedge.net/agnosupdate/boot-6a5ac08b5c458e24e810dd950185ee69b7c5f3556f9f43b323f1dba4e14f8d44.img.xz", + "hash": "6a5ac08b5c458e24e810dd950185ee69b7c5f3556f9f43b323f1dba4e14f8d44", + "hash_raw": "6a5ac08b5c458e24e810dd950185ee69b7c5f3556f9f43b323f1dba4e14f8d44", + "size": 14776320, "sparse": false, "full_check": true, "has_ab": true @@ -41,9 +41,9 @@ }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-5208f2d72b6d99bbee7dc038b3c95eccabc0bcabc5c718419e06bc7f897a675a.img.xz", - "hash": "68a3d0bb892c7b8347ce8b6d5a733a3f15d622af11febaeb3d6595308f15e738", - "hash_raw": "5208f2d72b6d99bbee7dc038b3c95eccabc0bcabc5c718419e06bc7f897a675a", + "url": "https://commadist.azureedge.net/agnosupdate/system-9056640f926b2612be503a9fec621091ae8a86ec3b2eeb15503db39490a6d2f4.img.xz", + "hash": "94445bb5db56bb2d462fa3831d3501cb8ffedafed9bf2e57128ffd71f454a4bd", + "hash_raw": "9056640f926b2612be503a9fec621091ae8a86ec3b2eeb15503db39490a6d2f4", "size": 10737418240, "sparse": true, "full_check": false, diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index ac41cbc3d..a4d527152 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -266,6 +266,8 @@ class Tici(HardwareBase): def set_power_save(self, powersave_enabled): # amplifier, 100mW at idle self.amplifier.set_global_shutdown(amp_disabled=powersave_enabled) + if not powersave_enabled: + self.amplifier.initialize_configuration() # offline big cluster, leave core 4 online for boardd for i in range(5, 8): diff --git a/selfdrive/hardware/tici/updater b/selfdrive/hardware/tici/updater index abea2ed17..e3442d59d 100755 Binary files a/selfdrive/hardware/tici/updater and b/selfdrive/hardware/tici/updater differ diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index d3ad01969..604f4f68d 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -31,7 +31,7 @@ INPUTS_WANTED = 50 # We want a little bit more than we need for stability MAX_ALLOWED_SPREAD = np.radians(2) RPY_INIT = np.array([0.0,0.0,0.0]) -# These values are needed to accomodate biggest modelframe +# These values are needed to accommodate biggest modelframe PITCH_LIMITS = np.array([-0.09074112085129739, 0.14907572052989657]) YAW_LIMITS = np.array([-0.06912048084718224, 0.06912048084718235]) DEBUG = os.getenv("DEBUG") is not None @@ -115,7 +115,7 @@ class Calibrator(): self.cal_status = Calibration.INVALID # If spread is too high, assume mounting was changed and reset to last block. - # Make the transition smooth. Abrupt transistion are not good foor feedback loop through supercombo model. + # Make the transition smooth. Abrupt transitions are not good foor feedback loop through supercombo model. if max(self.calib_spread) > MAX_ALLOWED_SPREAD and self.cal_status == Calibration.CALIBRATED: self.reset(self.rpys[self.block_idx - 1], valid_blocks=INPUTS_NEEDED, smooth_from=self.rpy) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 3f86ecf33..e49718af7 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -82,8 +82,9 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { //fix_pos_geo_std = np.abs(coord.ecef2geodetic(fix_ecef + fix_ecef_std) - fix_pos_geo) 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 device_from_ecef = quat2rot(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))).transpose(); - VectorXd calibrated_orientation_ecef = rot2euler(this->calib_from_device * device_from_ecef); + MatrixXdr device_from_ecef = euler2rot(orientation_ecef).transpose(); + //VectorXd calibrated_orientation_ecef = rot2euler(device_from_ecef); + 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); @@ -115,6 +116,7 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { VectorXd orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, orientation_ecef); //orientation_ned_std = ned_euler_from_ecef(fix_ecef, orientation_ecef + orientation_ecef_std) - orientation_ned + 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(); //ned_vel_std = self.converter->ecef2ned(fix_ecef + vel_ecef + vel_ecef_std) - self.converter->ecef2ned(fix_ecef + vel_ecef) @@ -137,6 +139,7 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, true); init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated); init_measurement(fix.initOrientationNED(), orientation_ned, nans, true); + init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, true); 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); diff --git a/selfdrive/locationd/ublox_msg.cc b/selfdrive/locationd/ublox_msg.cc index c84976fea..cda433345 100644 --- a/selfdrive/locationd/ublox_msg.cc +++ b/selfdrive/locationd/ublox_msg.cc @@ -117,7 +117,7 @@ std::pair> UbloxMsgParser::gen_msg() { return {"ubloxGnss", gen_mon_hw2(static_cast(body))}; break; default: - LOGE("Unkown message type %x", ubx_message.msg_type()); + LOGE("Unknown message type %x", ubx_message.msg_type()); return {"ubloxGnss", kj::Array()}; break; } diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 86c4473af..ece5d526c 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -12,8 +12,7 @@ static kj::Array build_boot_log() { boot.setWallTimeNanos(nanos_since_epoch()); std::string pstore = "/sys/fs/pstore"; - std::map pstore_map; - util::read_files_in_dir(pstore, &pstore_map); + std::map pstore_map = util::read_files_in_dir(pstore); const std::vector log_keywords = {"Kernel panic"}; auto lpstore = boot.initPstore().initEntries(pstore_map.size()); @@ -31,8 +30,7 @@ static kj::Array build_boot_log() { } } - std::string launchLog = util::read_file("/tmp/launch_log"); - boot.setLaunchLog(capnp::Text::Reader(launchLog.data(), launchLog.size())); + boot.setLaunchLog(util::read_file("/tmp/launch_log")); return capnp::messageToFlatArray(msg); } diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index 3f82b9f8b..b626073ce 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -2,8 +2,8 @@ import os from pathlib import Path from selfdrive.hardware import PC -if os.environ.get('LOGGERD_ROOT', False): - ROOT = os.environ['LOGGERD_ROOT'] +if os.environ.get('LOG_ROOT', False): + ROOT = os.environ['LOG_ROOT'] elif PC: ROOT = os.path.join(str(Path.home()), ".comma", "media", "0", "realdata") else: diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index 6436b960b..dccc226a3 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -60,7 +60,7 @@ kj::Array logger_build_init_data() { init.setDeviceType(cereal::InitData::DeviceType::PC); } - init.setVersion(capnp::Text::Reader(COMMA_VERSION)); + init.setVersion(COMMA_VERSION); std::ifstream cmdline_stream("/proc/cmdline"); std::vector kernel_args; @@ -94,23 +94,25 @@ kj::Array logger_build_init_data() { init.setDirty(!getenv("CLEAN")); // log params - Params params = Params(); - init.setGitCommit(params.get("GitCommit")); - init.setGitBranch(params.get("GitBranch")); - init.setGitRemote(params.get("GitRemote")); + auto params = Params(); + std::map params_map = params.readAll(); + + init.setGitCommit(params_map["GitCommit"]); + init.setGitBranch(params_map["GitBranch"]); + init.setGitRemote(params_map["GitRemote"]); init.setPassive(params.getBool("Passive")); - init.setDongleId(params.get("DongleId")); - { - std::map params_map; - params.readAll(¶ms_map); - auto lparams = init.initParams().initEntries(params_map.size()); - int i = 0; - for (auto& kv : params_map) { - auto lentry = lparams[i]; - lentry.setKey(kv.first); - lentry.setValue(capnp::Data::Reader((const kj::byte*)kv.second.data(), kv.second.size())); - i++; + init.setDongleId(params_map["DongleId"]); + + auto lparams = init.initParams().initEntries(params_map.size()); + int i = 0; + for (auto& [key, value] : params_map) { + auto lentry = lparams[i]; + lentry.setKey(key); + if ( !(params.getKeyType(key) & DONT_LOG) ) { + lentry.setValue(capnp::Data::Reader((const kj::byte*)value.data(), value.size())); } + i++; + } return capnp::messageToFlatArray(msg); } diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index 9d456680a..96c7a549b 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -15,11 +15,7 @@ #include "selfdrive/common/swaglog.h" #include "selfdrive/hardware/hw.h" -const std::string DEFAULT_LOG_ROOT = - Hardware::PC() ? util::getenv_default("HOME", "/.comma/media/0/realdata", "/data/media/0/realdata") - : "/data/media/0/realdata"; - -const std::string LOG_ROOT = util::getenv_default("LOG_ROOT", "", DEFAULT_LOG_ROOT.c_str()); +const std::string LOG_ROOT = Path::log_root(); #define LOGGER_MAX_HANDLES 16 @@ -43,7 +39,10 @@ class BZFile { } inline void write(void* data, size_t size) { int bzerror; - BZ2_bzWrite(&bzerror, bz_file, data, size); + do { + BZ2_bzWrite(&bzerror, bz_file, data, size); + } while (bzerror == BZ_IO_ERROR && errno == EINTR); + if (bzerror != BZ_OK && !error_logged) { LOGE("BZ2_bzWrite error, bzerror=%d", bzerror); error_logged = true; diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 9ae49fb3b..b2ecc4bc6 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -15,6 +15,7 @@ #include #include #include +#include #include "cereal/messaging/messaging.h" #include "cereal/services.h" @@ -59,7 +60,8 @@ LogCameraInfo cameras_logged[LOG_CAMERA_ID_MAX] = { .bitrate = MAIN_BITRATE, .is_h265 = true, .downscale = false, - .has_qcamera = true + .has_qcamera = true, + .trigger_rotate = true }, [LOG_CAMERA_ID_DCAMERA] = { .stream_type = VISION_STREAM_YUV_FRONT, @@ -69,7 +71,8 @@ LogCameraInfo cameras_logged[LOG_CAMERA_ID_MAX] = { .bitrate = DCAM_BITRATE, .is_h265 = true, .downscale = false, - .has_qcamera = false + .has_qcamera = false, + .trigger_rotate = Hardware::TICI(), }, [LOG_CAMERA_ID_ECAMERA] = { .stream_type = VISION_STREAM_YUV_WIDE, @@ -79,7 +82,8 @@ LogCameraInfo cameras_logged[LOG_CAMERA_ID_MAX] = { .bitrate = MAIN_BITRATE, .is_h265 = true, .downscale = false, - .has_qcamera = false + .has_qcamera = false, + .trigger_rotate = true }, [LOG_CAMERA_ID_QCAMERA] = { .filename = "qcamera.ts", @@ -92,81 +96,27 @@ LogCameraInfo cameras_logged[LOG_CAMERA_ID_MAX] = { }, }; -class RotateState { -public: - SubSocket* fpkt_sock; - uint32_t stream_frame_id, log_frame_id, last_rotate_frame_id; - bool enabled, should_rotate, initialized; - std::atomic rotating; - std::atomic cur_seg; - - RotateState() : fpkt_sock(nullptr), stream_frame_id(0), log_frame_id(0), - last_rotate_frame_id(UINT32_MAX), enabled(false), should_rotate(false), initialized(false), rotating(false), cur_seg(-1) {}; - - void waitLogThread() { - std::unique_lock lk(fid_lock); - while (stream_frame_id > log_frame_id // if the log camera is older, wait for it to catch up. - && (stream_frame_id - log_frame_id) < 8 // but if its too old then there probably was a discontinuity (visiond restarted) - && !do_exit) { - cv.wait(lk); - } - } - - void cancelWait() { - cv.notify_one(); - } - - void setStreamFrameId(uint32_t frame_id) { - fid_lock.lock(); - stream_frame_id = frame_id; - fid_lock.unlock(); - cv.notify_one(); - } - - void setLogFrameId(uint32_t frame_id) { - fid_lock.lock(); - log_frame_id = frame_id; - fid_lock.unlock(); - cv.notify_one(); - } - - void rotate() { - if (enabled) { - std::unique_lock lk(fid_lock); - should_rotate = true; - last_rotate_frame_id = stream_frame_id; - } - } - - void finish_rotate() { - std::unique_lock lk(fid_lock); - should_rotate = false; - } - -private: - std::mutex fid_lock; - std::condition_variable cv; -}; - struct LoggerdState { Context *ctx; LoggerState logger = {}; char segment_path[4096]; - int rotate_segment; - pthread_mutex_t rotate_lock; - RotateState rotate_state[LOG_CAMERA_ID_MAX-1]; + std::mutex rotate_lock; + std::condition_variable rotate_cv; + std::atomic rotate_segment; + std::atomic last_camera_seen_tms; + std::atomic waiting_rotate; + int max_waiting = 0; + double last_rotate_tms = 0.; }; LoggerdState s; void encoder_thread(int cam_idx) { assert(cam_idx < LOG_CAMERA_ID_MAX-1); - - LogCameraInfo &cam_info = cameras_logged[cam_idx]; - RotateState &rotate_state = s.rotate_state[cam_idx]; - + const LogCameraInfo &cam_info = cameras_logged[cam_idx]; set_thread_name(cam_info.filename); - int cnt = 0; + int cnt = 0, cur_seg = -1; + int encode_idx = 0; LoggerHandle *lh = NULL; std::vector encoders; VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); @@ -198,68 +148,47 @@ void encoder_thread(int cam_idx) { while (!do_exit) { VisionIpcBufExtra extra; VisionBuf* buf = vipc_client.recv(&extra); - if (buf == nullptr) { - continue; + if (buf == nullptr) continue; + + if (cam_info.trigger_rotate) { + s.last_camera_seen_tms = millis_since_boot(); } - //printf("logger latency to tsEof: %f\n", (double)(nanos_since_boot() - extra.timestamp_eof) / 1000000.0); + if (cam_info.trigger_rotate && (cnt >= SEGMENT_LENGTH * MAIN_FPS)) { + // trigger rotate and wait logger rotated to new segment + ++s.waiting_rotate; + std::unique_lock lk(s.rotate_lock); + s.rotate_cv.wait(lk, [&] { return s.rotate_segment > cur_seg || do_exit; }); + } + if (do_exit) break; - // all the rotation stuff - { - pthread_mutex_lock(&s.rotate_lock); - pthread_mutex_unlock(&s.rotate_lock); + // rotate the encoder if the logger is on a newer segment + if (s.rotate_segment > cur_seg) { + cur_seg = s.rotate_segment; + cnt = 0; - // wait if camera pkt id is older than stream - rotate_state.waitLogThread(); - - if (do_exit) break; - - // rotate the encoder if the logger is on a newer segment - if (rotate_state.should_rotate) { - LOGW("camera %d rotate encoder to %s", cam_idx, s.segment_path); - - if (!rotate_state.initialized) { - rotate_state.last_rotate_frame_id = extra.frame_id - 1; - rotate_state.initialized = true; - } - - // get new logger handle for new segment - if (lh) { - lh_close(lh); - } - lh = logger_get_handle(&s.logger); - - // wait for all to start rotating - rotate_state.rotating = true; - for(auto &r : s.rotate_state) { - while(r.enabled && !r.rotating && !do_exit) util::sleep_for(5); - } - - pthread_mutex_lock(&s.rotate_lock); - for (auto &e : encoders) { - e->encoder_close(); - e->encoder_open(s.segment_path); - } - rotate_state.cur_seg = s.rotate_segment; - pthread_mutex_unlock(&s.rotate_lock); - - // wait for all to finish rotating - for(auto &r : s.rotate_state) { - while(r.enabled && r.cur_seg != s.rotate_segment && !do_exit) util::sleep_for(5); - } - rotate_state.rotating = false; - rotate_state.finish_rotate(); + LOGW("camera %d rotate encoder to %s", cam_idx, s.segment_path); + for (auto &e : encoders) { + e->encoder_close(); + e->encoder_open(s.segment_path); } + if (lh) { + lh_close(lh); + } + lh = logger_get_handle(&s.logger); } - rotate_state.setStreamFrameId(extra.frame_id); - // encode a frame for (int i = 0; i < encoders.size(); ++i) { int out_id = encoders[i]->encode_frame(buf->y, buf->u, buf->v, buf->width, buf->height, extra.timestamp_eof); + + if (out_id == -1) { + LOGE("Failed to encode frame. frame_id: %d encode_id: %d", extra.frame_id, encode_idx); + } + + // publish encode index if (i == 0 && out_id != -1) { - // publish encode index MessageBuilder msg; // this is really ugly auto eidx = cam_idx == LOG_CAMERA_ID_DCAMERA ? msg.initEvent().initDriverEncodeIdx() : @@ -272,8 +201,8 @@ void encoder_thread(int cam_idx) { } else { eidx.setType(cam_idx == LOG_CAMERA_ID_DCAMERA ? cereal::EncodeIndex::Type::FRONT : cereal::EncodeIndex::Type::FULL_H_E_V_C); } - eidx.setEncodeId(cnt); - eidx.setSegmentNum(rotate_state.cur_seg); + eidx.setEncodeId(encode_idx); + eidx.setSegmentNum(cur_seg); eidx.setSegmentId(out_id); if (lh) { // TODO: this should read cereal/services.h for qlog decimation @@ -284,6 +213,7 @@ void encoder_thread(int cam_idx) { } cnt++; + encode_idx++; } if (lh) { @@ -311,6 +241,33 @@ void clear_locks() { ftw(LOG_ROOT.c_str(), clear_locks_fn, 16); } +void logger_rotate() { + { + std::unique_lock lk(s.rotate_lock); + int segment = -1; + int err = logger_next(&s.logger, LOG_ROOT.c_str(), s.segment_path, sizeof(s.segment_path), &segment); + assert(err == 0); + s.rotate_segment = segment; + s.waiting_rotate = 0; + s.last_rotate_tms = millis_since_boot(); + } + s.rotate_cv.notify_all(); + LOGW((s.logger.part == 0) ? "logging to %s" : "rotated to %s", s.segment_path); +} + +void rotate_if_needed() { + if (s.waiting_rotate == s.max_waiting) { + logger_rotate(); + } + + double tms = millis_since_boot(); + if ((tms - s.last_rotate_tms) > SEGMENT_LENGTH * 1000 && + (tms - s.last_camera_seen_tms) > NO_CAMERA_PATIENCE) { + LOGW("no camera packet seen. auto rotating"); + logger_rotate(); + } +} + } // namespace int main(int argc, char** argv) { @@ -322,11 +279,10 @@ int main(int argc, char** argv) { typedef struct QlogState { int counter, freq; } QlogState; - std::map qlog_states; + std::unordered_map qlog_states; s.ctx = Context::create(); Poller * poller = Poller::create(); - std::vector socks; // subscribe to all socks for (const auto& it : services) { @@ -335,13 +291,6 @@ int main(int argc, char** argv) { SubSocket * sock = SubSocket::create(s.ctx, it.name); assert(sock != NULL); poller->registerSocket(sock); - socks.push_back(sock); - - for (int cid=0; cid<=MAX_CAM_IDX; cid++) { - if (std::string(it.name) == cameras_logged[cid].frame_packet_name) { - s.rotate_state[cid].fpkt_sock = sock; - } - } qlog_states[sock] = {.counter = 0, .freq = it.decimation}; } @@ -349,124 +298,57 @@ int main(int argc, char** argv) { // init logger logger_init(&s.logger, "rlog", true); + logger_rotate(); params.put("CurrentRoute", s.logger.route_name); // init encoders - pthread_mutex_init(&s.rotate_lock, NULL); - + s.last_camera_seen_tms = millis_since_boot(); // TODO: create these threads dynamically on frame packet presence std::vector encoder_threads; encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_FCAMERA)); - s.rotate_state[LOG_CAMERA_ID_FCAMERA].enabled = true; + if (cameras_logged[LOG_CAMERA_ID_FCAMERA].trigger_rotate) { + s.max_waiting += 1; + } if (!Hardware::PC() && params.getBool("RecordFront")) { encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_DCAMERA)); - s.rotate_state[LOG_CAMERA_ID_DCAMERA].enabled = true; + if (cameras_logged[LOG_CAMERA_ID_DCAMERA].trigger_rotate) { + s.max_waiting += 1; + } } if (Hardware::TICI()) { encoder_threads.push_back(std::thread(encoder_thread, LOG_CAMERA_ID_ECAMERA)); - s.rotate_state[LOG_CAMERA_ID_ECAMERA].enabled = true; + if (cameras_logged[LOG_CAMERA_ID_ECAMERA].trigger_rotate) { + s.max_waiting += 1; + } } - uint64_t msg_count = 0; - uint64_t bytes_count = 0; - AlignedBuffer aligned_buf; - - double start_ts = seconds_since_boot(); - double last_rotate_tms = millis_since_boot(); - double last_camera_seen_tms = millis_since_boot(); + uint64_t msg_count = 0, bytes_count = 0; + double start_ts = millis_since_boot(); while (!do_exit) { - // TODO: fix msgs from the first poll getting dropped // poll for new messages on all sockets for (auto sock : poller->poll(1000)) { - // drain socket - Message * last_msg = nullptr; - while (!do_exit) { - Message * msg = sock->receive(true); - if (!msg) { - break; - } - delete last_msg; - last_msg = msg; - - QlogState& qs = qlog_states[sock]; - logger_log(&s.logger, (uint8_t*)msg->getData(), msg->getSize(), qs.counter == 0 && qs.freq != -1); - if (qs.freq != -1) { - qs.counter = (qs.counter + 1) % qs.freq; - } - + QlogState &qs = qlog_states[sock]; + Message *msg = nullptr; + while (!do_exit && (msg = sock->receive(true))) { + const bool in_qlog = qs.freq != -1 && (qs.counter++ % qs.freq == 0); + logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); bytes_count += msg->getSize(); + delete msg; + + rotate_if_needed(); + if ((++msg_count % 1000) == 0) { - double ts = seconds_since_boot(); - LOGD("%lu messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count * 1.0 / (ts - start_ts), bytes_count * 0.001 / (ts - start_ts)); + double seconds = (millis_since_boot() - start_ts) / 1000.0; + LOGD("%lu messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count / seconds, bytes_count * 0.001 / seconds); } } - - if (last_msg) { - int fpkt_id = -1; - for (int cid = 0; cid <=MAX_CAM_IDX; cid++) { - if (sock == s.rotate_state[cid].fpkt_sock) { - fpkt_id=cid; - break; - } - } - if (fpkt_id >= 0) { - // track camera frames to sync to encoder - // only process last frame - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(last_msg)); - cereal::Event::Reader event = cmsg.getRoot(); - - if (fpkt_id == LOG_CAMERA_ID_FCAMERA) { - s.rotate_state[fpkt_id].setLogFrameId(event.getRoadCameraState().getFrameId()); - } else if (fpkt_id == LOG_CAMERA_ID_DCAMERA) { - s.rotate_state[fpkt_id].setLogFrameId(event.getDriverCameraState().getFrameId()); - } else if (fpkt_id == LOG_CAMERA_ID_ECAMERA) { - s.rotate_state[fpkt_id].setLogFrameId(event.getWideRoadCameraState().getFrameId()); - } - last_camera_seen_tms = millis_since_boot(); - } - } - delete last_msg; - } - - bool new_segment = s.logger.part == -1; - if (s.logger.part > -1) { - double tms = millis_since_boot(); - if (tms - last_camera_seen_tms <= NO_CAMERA_PATIENCE && encoder_threads.size() > 0) { - new_segment = true; - for (auto &r : s.rotate_state) { - // this *should* be redundant on tici since all camera frames are synced - new_segment &= (((r.stream_frame_id >= r.last_rotate_frame_id + SEGMENT_LENGTH * MAIN_FPS) && - (!r.should_rotate) && (r.initialized)) || - (!r.enabled)); - if (!Hardware::TICI()) break; // only look at fcamera frame id if not QCOM2 - } - } else { - if (tms - last_rotate_tms > SEGMENT_LENGTH * 1000) { - new_segment = true; - LOGW("no camera packet seen. auto rotated"); - } - } - } - - // rotate to new segment - if (new_segment) { - pthread_mutex_lock(&s.rotate_lock); - last_rotate_tms = millis_since_boot(); - - int err = logger_next(&s.logger, LOG_ROOT.c_str(), s.segment_path, sizeof(s.segment_path), &s.rotate_segment); - assert(err == 0); - LOGW((s.logger.part == 0) ? "logging to %s" : "rotated to %s", s.segment_path); - - // rotate encoders - for (auto &r : s.rotate_state) r.rotate(); - pthread_mutex_unlock(&s.rotate_lock); } } LOGW("closing encoders"); - for (auto &r : s.rotate_state) r.cancelWait(); + s.rotate_cv.notify_all(); for (auto &t : encoder_threads) t.join(); LOGW("closing logger"); @@ -479,7 +361,7 @@ int main(int argc, char** argv) { } // messaging cleanup - for (auto sock : socks) delete sock; + for (auto &[sock, qs] : qlog_states) delete sock; delete poller; delete s.ctx; diff --git a/selfdrive/loggerd/omx_encoder.cc b/selfdrive/loggerd/omx_encoder.cc index 59c18c16b..e1fbba64a 100644 --- a/selfdrive/loggerd/omx_encoder.cc +++ b/selfdrive/loggerd/omx_encoder.cc @@ -21,9 +21,9 @@ #include "selfdrive/loggerd/include/msm_media_info.h" // Check the OMX error code and assert if an error occurred. -#define OMX_CHECK(_expr) \ - do { \ - assert(OMX_ErrorNone == _expr); \ +#define OMX_CHECK(_expr) \ + do { \ + assert(OMX_ErrorNone == (_expr)); \ } while (0) extern ExitHandler do_exit; diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index fdb9dbc5b..a5f91c935 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -37,7 +37,7 @@ def launcher(proc): except KeyboardInterrupt: cloudlog.warning("child %s got SIGINT" % proc) except Exception: - # can't install the crash handler becuase sys.excepthook doesn't play nice + # can't install the crash handler because sys.excepthook doesn't play nice # with threads, so catch it here. crash.capture_exception() raise @@ -228,7 +228,7 @@ class PythonProcess(ManagerProcess): class DaemonProcess(ManagerProcess): - """Python process that has to stay running accross manager restart. + """Python process that has to stay running across manager restart. This is used for athena so you don't lose SSH access when restarting manager.""" def __init__(self, name, module, param_name, enabled=True): self.name = name diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 91d256f24..128450540 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -20,6 +20,7 @@ procs = [ NativeProcess("ui", "selfdrive/ui", ["./ui"], persistent=True, watchdog_max_dt=(5 if TICI else None)), NativeProcess("soundd", "selfdrive/ui", ["./soundd"]), NativeProcess("locationd", "selfdrive/locationd", ["./locationd"]), + NativeProcess("boardd", "selfdrive/boardd", ["./boardd"], enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd"), PythonProcess("controlsd", "selfdrive.controls.controlsd"), PythonProcess("deleter", "selfdrive.loggerd.deleter", persistent=True), @@ -29,12 +30,15 @@ procs = [ PythonProcess("paramsd", "selfdrive.locationd.paramsd"), PythonProcess("plannerd", "selfdrive.controls.plannerd"), PythonProcess("radard", "selfdrive.controls.radard"), - PythonProcess("rtshield", "selfdrive.rtshield", enabled=EON), PythonProcess("thermald", "selfdrive.thermald.thermald", persistent=True), PythonProcess("timezoned", "selfdrive.timezoned", enabled=TICI, persistent=True), PythonProcess("tombstoned", "selfdrive.tombstoned", enabled=not PC, persistent=True), PythonProcess("updated", "selfdrive.updated", enabled=not PC, persistent=True), PythonProcess("uploader", "selfdrive.loggerd.uploader", persistent=True), + + # EON only + PythonProcess("rtshield", "selfdrive.rtshield", enabled=EON), + PythonProcess("androidd", "selfdrive.hardware.eon.androidd", enabled=EON, persistent=True), ] managed_processes = {p.name: p for p in procs} diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld index e84bbbf37..506f73163 100755 --- a/selfdrive/modeld/dmonitoringmodeld +++ b/selfdrive/modeld/dmonitoringmodeld @@ -1,15 +1,17 @@ #!/bin/sh -if [ -d /system ]; then - if [ -f /TICI ]; then # QCOM2 - export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" - else # QCOM - export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" - fi - export ADSP_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/dsp/" -else - # PC - export LD_LIBRARY_PATH="$HOME/openpilot/phonelibs/snpe/x86_64-linux-clang:/openpilot/phonelibs/snpe/x86_64:$HOME/openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" -fi +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR +if [ -d /system ]; then + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/phonelibs/snpe/larch64:$LD_LIBRARY_PATH" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/aarch64/:$LD_LIBRARY_PATH" + fi + export ADSP_LIBRARY_PATH="/data/pythonpath/phonelibs/snpe/dsp/" +else + # PC + export LD_LIBRARY_PATH="$DIR/../../phonelibs/snpe/x86_64-linux-clang:$DIR/../../openpilot/phonelibs/snpe/x86_64:$LD_LIBRARY_PATH" +fi exec ./_dmonitoringmodeld diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld index 1b67842ab..f3a7c2408 100755 --- a/selfdrive/modeld/modeld +++ b/selfdrive/modeld/modeld @@ -1,6 +1,7 @@ #!/bin/sh DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR if [ -d /system ]; then if [ -f /TICI ]; then # QCOM2 diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index f7a72b34e..3fb6f5625 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -24,7 +24,9 @@ constexpr int PLAN_MHP_SELECTION = 1; constexpr int PLAN_MHP_GROUP_SIZE = (2*PLAN_MHP_VALS + PLAN_MHP_SELECTION); constexpr int LEAD_MHP_N = 5; -constexpr int LEAD_MHP_VALS = 4; +constexpr int LEAD_TRAJ_LEN = 6; +constexpr int LEAD_PRED_DIM = 4; +constexpr int LEAD_MHP_VALS = LEAD_PRED_DIM*LEAD_TRAJ_LEN; constexpr int LEAD_MHP_SELECTION = 3; constexpr int LEAD_MHP_GROUP_SIZE = (2*LEAD_MHP_VALS + LEAD_MHP_SELECTION); @@ -147,18 +149,38 @@ void fill_sigmoid(const float *input, float *output, int len, int stride) { } } -void fill_lead_v2(cereal::ModelDataV2::LeadDataV2::Builder lead, const float *lead_data, const float *prob, int t_offset, float t) { +void fill_lead_v3(cereal::ModelDataV2::LeadDataV3::Builder lead, const float *lead_data, const float *prob, int t_offset, float prob_t) { + float t[LEAD_TRAJ_LEN] = {0.0, 2.0, 4.0, 6.0, 8.0, 10.0}; const float *data = get_lead_data(lead_data, t_offset); lead.setProb(sigmoid(prob[t_offset])); - lead.setT(t); - float xyva_arr[LEAD_MHP_VALS]; - float xyva_stds_arr[LEAD_MHP_VALS]; - for (int i=0; i None: # check health for lost heartbeat health = panda.health() if health["heartbeat_lost"]: + Params().put_bool("PandaHeartbeatLost", True) cloudlog.event("heartbeat lost", deviceState=health) cloudlog.info("Resetting panda") diff --git a/selfdrive/proclogd/SConscript b/selfdrive/proclogd/SConscript index f95f2597e..1b94a32f1 100644 --- a/selfdrive/proclogd/SConscript +++ b/selfdrive/proclogd/SConscript @@ -1,2 +1,6 @@ Import('env', 'cereal', 'messaging', 'common') -env.Program('proclogd.cc', LIBS=[cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj', 'common']) +libs = [cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj', 'common', 'zmq', 'json11'] +env.Program('proclogd', ['main.cc', 'proclog.cc'], LIBS=libs) + +if GetOption('test'): + env.Program('tests/test_proclog', ['tests/test_proclog.cc', 'proclog.cc'], LIBS=libs) diff --git a/selfdrive/proclogd/main.cc b/selfdrive/proclogd/main.cc new file mode 100644 index 000000000..4e31597c2 --- /dev/null +++ b/selfdrive/proclogd/main.cc @@ -0,0 +1,22 @@ + +#include + +#include "selfdrive/common/util.h" +#include "selfdrive/proclogd/proclog.h" + +ExitHandler do_exit; + +int main(int argc, char **argv) { + setpriority(PRIO_PROCESS, 0, -15); + + PubMaster publisher({"procLog"}); + while (!do_exit) { + MessageBuilder msg; + buildProcLogMessage(msg); + publisher.send("procLog", msg); + + util::sleep_for(2000); // 2 secs + } + + return 0; +} diff --git a/selfdrive/proclogd/proclog.cc b/selfdrive/proclogd/proclog.cc new file mode 100644 index 000000000..adc828cb5 --- /dev/null +++ b/selfdrive/proclogd/proclog.cc @@ -0,0 +1,239 @@ +#include "selfdrive/proclogd/proclog.h" + +#include + +#include +#include +#include +#include + +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/util.h" + +namespace Parser { + +// parse /proc/stat +std::vector cpuTimes(std::istream &stream) { + std::vector cpu_times; + std::string line; + // skip the first line for cpu total + std::getline(stream, line); + while (std::getline(stream, line)) { + if (line.compare(0, 3, "cpu") != 0) break; + + CPUTime t = {}; + std::istringstream iss(line); + if (iss.ignore(3) >> t.id >> t.utime >> t.ntime >> t.stime >> t.itime >> t.iowtime >> t.irqtime >> t.sirqtime) + cpu_times.push_back(t); + } + return cpu_times; +} + +// parse /proc/meminfo +std::unordered_map memInfo(std::istream &stream) { + std::unordered_map mem_info; + std::string line, key; + while (std::getline(stream, line)) { + uint64_t val = 0; + std::istringstream iss(line); + if (iss >> key >> val) { + mem_info[key] = val * 1024; + } + } + return mem_info; +} + +// field position (https://man7.org/linux/man-pages/man5/proc.5.html) +enum StatPos { + pid = 1, + state = 3, + ppid = 4, + utime = 14, + stime = 15, + cutime = 16, + cstime = 17, + priority = 18, + nice = 19, + num_threads = 20, + starttime = 22, + vsize = 23, + rss = 24, + processor = 39, + MAX_FIELD = 52, +}; + +// parse /proc/pid/stat +std::optional procStat(std::string stat) { + // To avoid being fooled by names containing a closing paren, scan backwards. + auto open_paren = stat.find('('); + auto close_paren = stat.rfind(')'); + if (open_paren == std::string::npos || close_paren == std::string::npos || open_paren > close_paren) { + return std::nullopt; + } + + std::string name = stat.substr(open_paren + 1, close_paren - open_paren - 1); + // repace space in name with _ + std::replace(&stat[open_paren], &stat[close_paren], ' ', '_'); + std::istringstream iss(stat); + std::vector v{std::istream_iterator(iss), + std::istream_iterator()}; + try { + if (v.size() != StatPos::MAX_FIELD) { + throw std::invalid_argument("stat"); + } + ProcStat p = { + .name = name, + .pid = stoi(v[StatPos::pid - 1]), + .state = v[StatPos::state - 1][0], + .ppid = stoi(v[StatPos::ppid - 1]), + .utime = stoul(v[StatPos::utime - 1]), + .stime = stoul(v[StatPos::stime - 1]), + .cutime = stol(v[StatPos::cutime - 1]), + .cstime = stol(v[StatPos::cstime - 1]), + .priority = stol(v[StatPos::priority - 1]), + .nice = stol(v[StatPos::nice - 1]), + .num_threads = stol(v[StatPos::num_threads - 1]), + .starttime = stoull(v[StatPos::starttime - 1]), + .vms = stoul(v[StatPos::vsize - 1]), + .rss = stoul(v[StatPos::rss - 1]), + .processor = stoi(v[StatPos::processor - 1]), + }; + return p; + } catch (const std::invalid_argument &e) { + LOGE("failed to parse procStat (%s) :%s", e.what(), stat.c_str()); + } catch (const std::out_of_range &e) { + LOGE("failed to parse procStat (%s) :%s", e.what(), stat.c_str()); + } + return std::nullopt; +} + +// return list of PIDs from /proc +std::vector pids() { + std::vector ids; + DIR *d = opendir("/proc"); + assert(d); + char *p_end; + struct dirent *de = NULL; + while ((de = readdir(d))) { + if (de->d_type == DT_DIR) { + int pid = strtol(de->d_name, &p_end, 10); + if (p_end == (de->d_name + strlen(de->d_name))) { + ids.push_back(pid); + } + } + } + closedir(d); + return ids; +} + +// null-delimited cmdline arguments to vector +std::vector cmdline(std::istream &stream) { + std::vector ret; + std::string line; + while (std::getline(stream, line, '\0')) { + if (!line.empty()) { + ret.push_back(line); + } + } + return ret; +} + +const ProcCache &getProcExtraInfo(int pid, const std::string &name) { + static std::unordered_map proc_cache; + ProcCache &cache = proc_cache[pid]; + if (cache.pid != pid || cache.name != name) { + cache.pid = pid; + cache.name = name; + std::string proc_path = "/proc/" + std::to_string(pid); + cache.exe = util::readlink(proc_path + "/exe"); + std::ifstream stream(proc_path + "/cmdline"); + cache.cmdline = cmdline(stream); + } + return cache; +} + +} // namespace Parser + +const double jiffy = sysconf(_SC_CLK_TCK); +const size_t page_size = sysconf(_SC_PAGE_SIZE); + +void buildCPUTimes(cereal::ProcLog::Builder &builder) { + std::ifstream stream("/proc/stat"); + std::vector stats = Parser::cpuTimes(stream); + + auto log_cpu_times = builder.initCpuTimes(stats.size()); + for (int i = 0; i < stats.size(); ++i) { + auto l = log_cpu_times[i]; + const CPUTime &r = stats[i]; + l.setCpuNum(r.id); + l.setUser(r.utime / jiffy); + l.setNice(r.ntime / jiffy); + l.setSystem(r.stime / jiffy); + l.setIdle(r.itime / jiffy); + l.setIowait(r.iowtime / jiffy); + l.setIrq(r.irqtime / jiffy); + l.setSoftirq(r.sirqtime / jiffy); + } +} + +void buildMemInfo(cereal::ProcLog::Builder &builder) { + std::ifstream stream("/proc/meminfo"); + auto mem_info = Parser::memInfo(stream); + + auto mem = builder.initMem(); + mem.setTotal(mem_info["MemTotal:"]); + mem.setFree(mem_info["MemFree:"]); + mem.setAvailable(mem_info["MemAvailable:"]); + mem.setBuffers(mem_info["Buffers:"]); + mem.setCached(mem_info["Cached:"]); + mem.setActive(mem_info["Active:"]); + mem.setInactive(mem_info["Inactive:"]); + mem.setShared(mem_info["Shmem:"]); +} + +void buildProcs(cereal::ProcLog::Builder &builder) { + auto pids = Parser::pids(); + std::vector proc_stats; + proc_stats.reserve(pids.size()); + for (int pid : pids) { + std::string path = "/proc/" + std::to_string(pid) + "/stat"; + if (auto stat = Parser::procStat(util::read_file(path))) { + proc_stats.push_back(*stat); + } + } + + auto procs = builder.initProcs(proc_stats.size()); + for (size_t i = 0; i < proc_stats.size(); i++) { + auto l = procs[i]; + const ProcStat &r = proc_stats[i]; + l.setPid(r.pid); + l.setState(r.state); + l.setPpid(r.ppid); + l.setCpuUser(r.utime / jiffy); + l.setCpuSystem(r.stime / jiffy); + l.setCpuChildrenUser(r.cutime / jiffy); + l.setCpuChildrenSystem(r.cstime / jiffy); + l.setPriority(r.priority); + l.setNice(r.nice); + l.setNumThreads(r.num_threads); + l.setStartTime(r.starttime / jiffy); + l.setMemVms(r.vms); + l.setMemRss((uint64_t)r.rss * page_size); + l.setProcessor(r.processor); + l.setName(r.name); + + const ProcCache &extra_info = Parser::getProcExtraInfo(r.pid, r.name); + l.setExe(extra_info.exe); + auto lcmdline = l.initCmdline(extra_info.cmdline.size()); + for (size_t i = 0; i < lcmdline.size(); i++) { + lcmdline.set(i, extra_info.cmdline[i]); + } + } +} + +void buildProcLogMessage(MessageBuilder &msg) { + auto procLog = msg.initEvent().initProcLog(); + buildProcs(procLog); + buildCPUTimes(procLog); + buildMemInfo(procLog); +} diff --git a/selfdrive/proclogd/proclog.h b/selfdrive/proclogd/proclog.h new file mode 100644 index 000000000..9ed53d1ba --- /dev/null +++ b/selfdrive/proclogd/proclog.h @@ -0,0 +1,40 @@ +#include +#include +#include +#include + +#include "cereal/messaging/messaging.h" + +struct CPUTime { + int id; + unsigned long utime, ntime, stime, itime; + unsigned long iowtime, irqtime, sirqtime; +}; + +struct ProcCache { + int pid; + std::string name, exe; + std::vector cmdline; +}; + +struct ProcStat { + int pid, ppid, processor; + char state; + long cutime, cstime, priority, nice, num_threads; + unsigned long utime, stime, vms, rss; + unsigned long long starttime; + std::string name; +}; + +namespace Parser { + +std::vector pids(); +std::optional procStat(std::string stat); +std::vector cmdline(std::istream &stream); +std::vector cpuTimes(std::istream &stream); +std::unordered_map memInfo(std::istream &stream); +const ProcCache &getProcExtraInfo(int pid, const std::string &name); + +}; // namespace Parser + +void buildProcLogMessage(MessageBuilder &msg); diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc deleted file mode 100644 index af7a6e3f2..000000000 --- a/selfdrive/proclogd/proclogd.cc +++ /dev/null @@ -1,233 +0,0 @@ -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "selfdrive/common/timing.h" -#include "selfdrive/common/util.h" - -ExitHandler do_exit; - -namespace { -struct ProcCache { - std::string name; - std::vector cmdline; - std::string exe; -}; - -} - -int main() { - setpriority(PRIO_PROCESS, 0, -15); - - PubMaster publisher({"procLog"}); - - double jiffy = sysconf(_SC_CLK_TCK); - size_t page_size = sysconf(_SC_PAGE_SIZE); - - std::unordered_map proc_cache; - - while (!do_exit) { - - MessageBuilder msg; - auto procLog = msg.initEvent().initProcLog(); - auto orphanage = msg.getOrphanage(); - - // stat - { - std::vector> otimes; - - std::ifstream sstat("/proc/stat"); - std::string stat_line; - while (std::getline(sstat, stat_line)) { - if (util::starts_with(stat_line, "cpu ")) { - // cpu total - } else if (util::starts_with(stat_line, "cpu")) { - // specific cpu - int id; - unsigned long utime, ntime, stime, itime; - unsigned long iowtime, irqtime, sirqtime; - - sscanf(stat_line.data(), "cpu%d %lu %lu %lu %lu %lu %lu %lu", - &id, &utime, &ntime, &stime, &itime, &iowtime, &irqtime, &sirqtime); - - auto ltimeo = orphanage.newOrphan(); - auto ltime = ltimeo.get(); - ltime.setCpuNum(id); - ltime.setUser(utime / jiffy); - ltime.setNice(ntime / jiffy); - ltime.setSystem(stime / jiffy); - ltime.setIdle(itime / jiffy); - ltime.setIowait(iowtime / jiffy); - ltime.setIrq(irqtime / jiffy); - ltime.setSoftirq(irqtime / jiffy); - - otimes.push_back(std::move(ltimeo)); - - } else { - break; - } - } - - auto ltimes = procLog.initCpuTimes(otimes.size()); - for (size_t i = 0; i < otimes.size(); i++) { - ltimes.adoptWithCaveats(i, std::move(otimes[i])); - } - } - - // meminfo - { - auto mem = procLog.initMem(); - - std::ifstream smem("/proc/meminfo"); - std::string mem_line; - - uint64_t mem_total = 0, mem_free = 0, mem_available = 0, mem_buffers = 0; - uint64_t mem_cached = 0, mem_active = 0, mem_inactive = 0, mem_shared = 0; - - while (std::getline(smem, mem_line)) { - if (util::starts_with(mem_line, "MemTotal:")) sscanf(mem_line.data(), "MemTotal: %" SCNu64 " kB", &mem_total); - else if (util::starts_with(mem_line, "MemFree:")) sscanf(mem_line.data(), "MemFree: %" SCNu64 " kB", &mem_free); - else if (util::starts_with(mem_line, "MemAvailable:")) sscanf(mem_line.data(), "MemAvailable: %" SCNu64 " kB", &mem_available); - else if (util::starts_with(mem_line, "Buffers:")) sscanf(mem_line.data(), "Buffers: %" SCNu64 " kB", &mem_buffers); - else if (util::starts_with(mem_line, "Cached:")) sscanf(mem_line.data(), "Cached: %" SCNu64 " kB", &mem_cached); - else if (util::starts_with(mem_line, "Active:")) sscanf(mem_line.data(), "Active: %" SCNu64 " kB", &mem_active); - else if (util::starts_with(mem_line, "Inactive:")) sscanf(mem_line.data(), "Inactive: %" SCNu64 " kB", &mem_inactive); - else if (util::starts_with(mem_line, "Shmem:")) sscanf(mem_line.data(), "Shmem: %" SCNu64 " kB", &mem_shared); - } - - mem.setTotal(mem_total * 1024); - mem.setFree(mem_free * 1024); - mem.setAvailable(mem_available * 1024); - mem.setBuffers(mem_buffers * 1024); - mem.setCached(mem_cached * 1024); - mem.setActive(mem_active * 1024); - mem.setInactive(mem_inactive * 1024); - mem.setShared(mem_shared * 1024); - } - - // processes - { - std::vector> oprocs; - struct dirent *de = NULL; - DIR *d = opendir("/proc"); - assert(d); - while ((de = readdir(d))) { - if (!isdigit(de->d_name[0])) continue; - pid_t pid = atoi(de->d_name); - - - auto lproco = orphanage.newOrphan(); - auto lproc = lproco.get(); - - lproc.setPid(pid); - - char tcomm[PATH_MAX] = {0}; - - { - std::string stat = util::read_file(util::string_format("/proc/%d/stat", pid)); - - char state; - - int ppid; - unsigned long utime, stime; - long cutime, cstime, priority, nice, num_threads; - unsigned long long starttime; - unsigned long vms, rss; - int processor; - - int count = sscanf(stat.data(), - "%*d (%1024[^)]) %c %d %*d %*d %*d %*d %*d %*d %*d %*d %*d " - "%lu %lu %ld %ld %ld %ld %ld %*d %lld " - "%lu %lu %*d %*d %*d %*d %*d %*d %*d " - "%*d %*d %*d %*d %*d %*d %*d %d", - tcomm, &state, &ppid, - &utime, &stime, &cutime, &cstime, &priority, &nice, &num_threads, &starttime, - &vms, &rss, &processor); - - if (count != 14) continue; - - lproc.setState(state); - lproc.setPpid(ppid); - lproc.setCpuUser(utime / jiffy); - lproc.setCpuSystem(stime / jiffy); - lproc.setCpuChildrenUser(cutime / jiffy); - lproc.setCpuChildrenSystem(cstime / jiffy); - lproc.setPriority(priority); - lproc.setNice(nice); - lproc.setNumThreads(num_threads); - lproc.setStartTime(starttime / jiffy); - lproc.setMemVms(vms); - lproc.setMemRss((uint64_t)rss * page_size); - lproc.setProcessor(processor); - } - - std::string name(tcomm); - lproc.setName(name); - - // populate other things from cache - auto cache_it = proc_cache.find(pid); - ProcCache cache; - if (cache_it != proc_cache.end()) { - cache = cache_it->second; - } - if (cache_it == proc_cache.end() || cache.name != name) { - cache = (ProcCache){ - .name = name, - .exe = util::readlink(util::string_format("/proc/%d/exe", pid)), - }; - - // null-delimited cmdline arguments to vector - std::string cmdline_s = util::read_file(util::string_format("/proc/%d/cmdline", pid)); - const char* cmdline_p = cmdline_s.c_str(); - const char* cmdline_ep = cmdline_p + cmdline_s.size(); - - // strip trailing null bytes - while ((cmdline_ep-1) > cmdline_p && *(cmdline_ep-1) == 0) { - cmdline_ep--; - } - - while (cmdline_p < cmdline_ep) { - std::string arg(cmdline_p); - cache.cmdline.push_back(arg); - cmdline_p += arg.size() + 1; - } - - proc_cache[pid] = cache; - } - - auto lcmdline = lproc.initCmdline(cache.cmdline.size()); - for (size_t i = 0; i < lcmdline.size(); i++) { - lcmdline.set(i, cache.cmdline[i]); - } - lproc.setExe(cache.exe); - - oprocs.push_back(std::move(lproco)); - } - closedir(d); - - auto lprocs = procLog.initProcs(oprocs.size()); - for (size_t i = 0; i < oprocs.size(); i++) { - lprocs.adoptWithCaveats(i, std::move(oprocs[i])); - } - } - - publisher.send("procLog", msg); - - util::sleep_for(2000); // 2 secs - } - - return 0; -} diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord index d2bffaa12..9ea848d57 100755 --- a/selfdrive/sensord/sensord +++ b/selfdrive/sensord/sensord @@ -1,3 +1,4 @@ #!/bin/sh +cd "$(dirname "$0")" export LD_LIBRARY_PATH="/system/lib64:$LD_LIBRARY_PATH" exec ./_sensord diff --git a/selfdrive/sensord/sensors/bmx055_magn.cc b/selfdrive/sensord/sensors/bmx055_magn.cc index e7a8de909..29e0d809d 100644 --- a/selfdrive/sensord/sensors/bmx055_magn.cc +++ b/selfdrive/sensord/sensors/bmx055_magn.cc @@ -245,6 +245,6 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) { // The BMX055 Magnetometer has no FIFO mode. Self running mode only goes // up to 30 Hz. Therefore we put in forced mode, and request measurements // at a 100 Hz. When reading the registers we have to check the ready bit - // To verify the measurement was comleted this cycle. + // To verify the measurement was completed this cycle. set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED); } diff --git a/selfdrive/sensord/sensors/mmc5603nj_magn.cc b/selfdrive/sensord/sensors/mmc5603nj_magn.cc index 829a7f7d2..68878867e 100644 --- a/selfdrive/sensord/sensors/mmc5603nj_magn.cc +++ b/selfdrive/sensord/sensors/mmc5603nj_magn.cc @@ -41,7 +41,7 @@ int MMC5603NJ_Magn::init() { goto fail; } - // Enable continous mode, set every 100 measurements + // Enable continuous mode, set every 100 measurements ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_2, MMC5603NJ_CMM_EN | MMC5603NJ_EN_PRD_SET | 0b11); if (ret < 0) { goto fail; diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index b5b7e3be0..342f28c2c 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -13,7 +13,7 @@ from cereal.services import service_list from common.basedir import BASEDIR from common.timeout import Timeout from common.params import Params -from selfdrive.hardware import TICI +from selfdrive.hardware import EON, TICI from selfdrive.loggerd.config import ROOT from selfdrive.test.helpers import set_params_enabled from tools.lib.logreader import LogReader @@ -44,11 +44,16 @@ PROCS = { "./logcatd": 0, } +if EON: + PROCS.update({ + "selfdrive.hardware.eon.androidd": 0.4, + }) + if TICI: PROCS.update({ "./loggerd": 60.0, - "selfdrive.controls.controlsd": 26.0, - "./camerad": 25.0, + "selfdrive.controls.controlsd": 28.0, + "./camerad": 31.0, "./_ui": 21.0, "selfdrive.controls.plannerd": 12.0, "selfdrive.locationd.paramsd": 5.0, @@ -75,7 +80,10 @@ def check_cpu_usage(first_proc, last_proc): last = [p for p in last_proc.procLog.procs if proc_name in p.cmdline][0] cpu_time = cputime_total(last) - cputime_total(first) cpu_usage = cpu_time / dt * 100. - if cpu_usage > max(normal_cpu_usage * 1.1, normal_cpu_usage + 5.0): + if cpu_usage > max(normal_cpu_usage * 1.15, normal_cpu_usage + 5.0): + # cpu usage is high while playing sounds + if proc_name == "./_soundd" and cpu_usage < 25.: + continue result += f"Warning {proc_name} using more CPU than normal\n" r = False elif cpu_usage < min(normal_cpu_usage * 0.65, max(normal_cpu_usage - 1.0, 0.0)): @@ -154,7 +162,7 @@ class TestOnroad(unittest.TestCase): def test_model_timings(self): #TODO this went up when plannerd cpu usage increased, why? - cfgs = [("modelV2", 0.035, 0.03), ("driverState", 0.025, 0.021)] + cfgs = [("modelV2", 0.038, 0.036), ("driverState", 0.028, 0.026)] for (s, instant_max, avg_max) in cfgs: ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s] self.assertLess(min(ts), instant_max, f"high '{s}' execution time: {min(ts)}") diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index bcd3f1888..dac7b4e8f 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -259,7 +259,7 @@ def thermald_thread(): msg.deviceState.freeSpacePercent = get_available_percent(default=100.0) msg.deviceState.memoryUsagePercent = int(round(psutil.virtual_memory().percent)) - msg.deviceState.cpuUsagePercent = int(round(psutil.cpu_percent())) + msg.deviceState.cpuUsagePercent = [int(round(n)) for n in psutil.cpu_percent(percpu=True)] msg.deviceState.gpuUsagePercent = int(round(HARDWARE.get_gpu_usage_percent())) msg.deviceState.networkType = network_type msg.deviceState.networkStrength = network_strength diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 61ca8c868..a4836cdb7 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -63,7 +63,6 @@ if arch != 'aarch64' and GetOption('setup'): asset_obj = qt_env.Object("assets", assets) qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs) - qt_env.Program("qt/setup/wifi", ["qt/setup/wifi.cc"], LIBS=qt_libs + ['common', 'json11']) qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs) qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj], LIBS=qt_libs + ['curl', 'common', 'json11']) @@ -71,14 +70,21 @@ if arch != 'aarch64' and GetOption('setup'): senv = qt_env.Clone() senv['LINKFLAGS'].append('-Wl,-strip-debug') installers = [ - ("openpilot", "release3-staging"), + ("openpilot", "release3"), ("openpilot_test", "release3-staging"), + ("openpilot_nightly", "master-ci"), ("openpilot_internal", "master"), - ("dashcam", "dashcam3-staging"), + ("dashcam", "dashcam3"), ("dashcam_test", "dashcam3-staging"), ] + + cont = {} + for brand in ("openpilot", "dashcam"): + cont[brand] = senv.Command(f"qt/setup/continue_{brand}.o", f"#installer/continue_{brand}.sh", + "ld -r -b binary -o $TARGET $SOURCE") for name, branch in installers: - d = {'BRANCH': f"'\"{branch}\"'"} + brand = "dashcam" if "dashcam" in branch else "openpilot" + d = {'BRANCH': f"'\"{branch}\"'", 'BRAND': f"'\"{brand}\"'"} if "internal" in name: d['INTERNAL'] = "1" @@ -87,7 +93,7 @@ if arch != 'aarch64' and GetOption('setup'): r.raise_for_status() d['SSH_KEYS'] = f'\\"{r.text.strip()}\\"' obj = senv.Object(f"qt/setup/installer_{name}.o", ["qt/setup/installer.cc"], CPPDEFINES=d) - f = senv.Program(f"qt/setup/installer_{name}", obj, LIBS=qt_libs) + f = senv.Program(f"qt/setup/installer_{name}", [obj, cont[brand]], LIBS=qt_libs) # keep installers small assert f[0].get_size() < 300*1e3 diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc index ac944fd87..40972e07a 100644 --- a/selfdrive/ui/paint.cc +++ b/selfdrive/ui/paint.cc @@ -67,15 +67,15 @@ static void ui_draw_circle_image(const UIState *s, int center_x, int center_y, i ui_draw_circle_image(s, center_x, center_y, radius, image, nvgRGBA(0, 0, 0, (255 * bg_alpha)), img_alpha); } -static void draw_lead(UIState *s, const cereal::RadarState::LeadData::Reader &lead_data, const vertex_data &vd) { +static void draw_lead(UIState *s, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const vertex_data &vd) { // Draw lead car indicator auto [x, y] = vd; float fillAlpha = 0; float speedBuff = 10.; float leadBuff = 40.; - float d_rel = lead_data.getDRel(); - float v_rel = lead_data.getVRel(); + float d_rel = lead_data.getX()[0]; + float v_rel = lead_data.getV()[0]; if (d_rel < leadBuff) { fillAlpha = 255*(1.0-(d_rel/leadBuff)); if (v_rel < 0) { @@ -167,13 +167,12 @@ static void ui_draw_world(UIState *s) { // Draw lead indicators if openpilot is handling longitudinal if (s->scene.longitudinal_control) { - auto radar_state = (*s->sm)["radarState"].getRadarState(); - auto lead_one = radar_state.getLeadOne(); - auto lead_two = radar_state.getLeadTwo(); - if (lead_one.getStatus()) { + auto lead_one = (*s->sm)["modelV2"].getModelV2().getLeadsV3()[0]; + auto lead_two = (*s->sm)["modelV2"].getModelV2().getLeadsV3()[1]; + if (lead_one.getProb() > .5) { draw_lead(s, lead_one, s->scene.lead_vertices[0]); } - if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { + if (lead_two.getProb() > .5 && (std::abs(lead_one.getX()[0] - lead_two.getX()[0]) > 3.0)) { draw_lead(s, lead_two, s->scene.lead_vertices[1]); } } diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc index bfb3d8a1d..90ba5fd53 100644 --- a/selfdrive/ui/qt/api.cc +++ b/selfdrive/ui/qt/api.cc @@ -14,15 +14,12 @@ #include "selfdrive/common/params.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" +#include "selfdrive/ui/qt/util.h" namespace CommaApi { -const std::string private_key_path = - Hardware::PC() ? util::getenv_default("HOME", "/.comma/persist/comma/id_rsa", "/persist/comma/id_rsa") - : "/persist/comma/id_rsa"; - QByteArray rsa_sign(const QByteArray &data) { - auto file = QFile(private_key_path.c_str()); + auto file = QFile(Path::rsa_file().c_str()); if (!file.open(QIODevice::ReadOnly)) { qDebug() << "No RSA private key found, please run manager.py or registration.py"; return QByteArray(); @@ -48,9 +45,8 @@ QByteArray rsa_sign(const QByteArray &data) { QString create_jwt(const QJsonObject &payloads, int expiry) { QJsonObject header = {{"alg", "RS256"}}; - QString dongle_id = QString::fromStdString(Params().get("DongleId")); auto t = QDateTime::currentSecsSinceEpoch(); - QJsonObject payload = {{"identity", dongle_id}, {"nbf", t}, {"iat", t}, {"exp", t + expiry}}; + QJsonObject payload = {{"identity", getDongleId().value_or("")}, {"nbf", t}, {"iat", t}, {"exp", t + expiry}}; for (auto it = payloads.begin(); it != payloads.end(); ++it) { payload.insert(it.key(), it.value()); } @@ -89,7 +85,7 @@ void HttpRequest::sendRequest(const QString &requestURL, const HttpRequest::Meth if(create_jwt) { token = CommaApi::create_jwt(); } else { - QString token_json = QString::fromStdString(util::read_file(util::getenv_default("HOME", "/.comma/auth.json", "/.comma/auth.json"))); + QString token_json = QString::fromStdString(util::read_file(util::getenv("HOME") + "/.comma/auth.json")); QJsonDocument json_d = QJsonDocument::fromJson(token_json.toUtf8()); token = json_d["access_token"].toString(); } diff --git a/selfdrive/ui/qt/api.h b/selfdrive/ui/qt/api.h index 624e58bd6..1c7c333ea 100644 --- a/selfdrive/ui/qt/api.h +++ b/selfdrive/ui/qt/api.h @@ -5,8 +5,11 @@ #include #include +#include "selfdrive/common/util.h" + namespace CommaApi { +const QString BASE_URL = util::getenv("API_HOST", "https://api.commadotai.com").c_str(); QByteArray rsa_sign(const QByteArray &data); QString create_jwt(const QJsonObject &payloads = {}, int expiry = 3600); diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 428b5e202..a6f02bc00 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -158,10 +158,10 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { font-size: 55px; } )"); - refresh(); } void OffroadHome::showEvent(QShowEvent *event) { + refresh(); timer->start(10 * 1000); } diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index 4db9ce5e7..c1e1fa163 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -129,7 +129,7 @@ void MapWindow::timerUpdate() { if (localizer_valid) { auto pos = location.getPositionGeodetic(); - auto orientation = location.getOrientationNED(); + auto orientation = location.getCalibratedOrientationNED(); float velocity = location.getVelocityCalibrated().getValue()[0]; float bearing = RAD2DEG(orientation.getValue()[2]); @@ -198,7 +198,7 @@ void MapWindow::timerUpdate() { } // Transition to next route segment - if (distance_to_maneuver < -MANEUVER_TRANSITION_THRESHOLD) { + if (!shouldRecompute() && (distance_to_maneuver < -MANEUVER_TRANSITION_THRESHOLD)) { auto next_segment = segment.nextRouteSegment(); if (next_segment.isValid()) { segment = next_segment; diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 16730e6c5..cdfa4b3ce 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -17,7 +17,7 @@ QMapbox::CoordinatesCollections model_to_collection( 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).transpose(); + Eigen::Matrix3d ecef_from_local = euler2rot(orient); QMapbox::Coordinates coordinates; auto x = line.getX(); diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc index 4e5d4ea48..c91f1c586 100644 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ b/selfdrive/ui/qt/maps/map_settings.cc @@ -93,19 +93,18 @@ MapPanel::MapPanel(QWidget* parent) : QWidget(parent) { clear(); - std::string dongle_id = params.get("DongleId"); - if (util::is_valid_dongle_id(dongle_id)) { + if (auto dongle_id = getDongleId()) { // Fetch favorite and recent locations { - std::string url = "https://api.commadotai.com/v1/navigation/" + dongle_id + "/locations"; - RequestRepeater* repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_NavDestinations", 30, true); + QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/locations"; + RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_NavDestinations", 30, true); QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &MapPanel::parseResponse); QObject::connect(repeater, &RequestRepeater::failedResponse, this, &MapPanel::failedResponse); } // Destination set while offline { - QString url = QString::fromStdString("https://api.commadotai.com/v1/navigation/" + dongle_id + "/next"); + QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/next"; RequestRepeater* repeater = new RequestRepeater(this, url, "", 10, true); HttpRequest* deleter = new HttpRequest(this); diff --git a/selfdrive/ui/qt/offroad/onboarding.h b/selfdrive/ui/qt/offroad/onboarding.h index c35ce069d..980d450b7 100644 --- a/selfdrive/ui/qt/offroad/onboarding.h +++ b/selfdrive/ui/qt/offroad/onboarding.h @@ -72,8 +72,8 @@ private: QRect(303, 755, 718, 189), }; - const QString IMG_PATH = vwp_w == 2160 ? "../assets/training_wide/" : "../assets/training/"; - const QVector boundingRect = vwp_w == 2160 ? boundingRectWide : boundingRectStandard; + const QString IMG_PATH = WIDE_UI ? "../assets/training_wide/" : "../assets/training/"; + const QVector boundingRect = WIDE_UI ? boundingRectWide : boundingRectStandard; signals: void completedTraining(); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 66a808fd0..082fe68be 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -96,9 +96,7 @@ TogglesPanel::TogglesPanel(QWidget *parent) : QWidget(parent) { DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) { QVBoxLayout *main_layout = new QVBoxLayout(this); Params params = Params(); - - QString dongle = QString::fromStdString(params.get("DongleId", false)); - main_layout->addWidget(new LabelControl("Dongle ID", dongle)); + main_layout->addWidget(new LabelControl("Dongle ID", getDongleId().value_or("N/A"))); main_layout->addWidget(horizontal_line()); QString serial = QString::fromStdString(params.get("HardwareSerial", false)); diff --git a/selfdrive/ui/qt/offroad/wifiManager.cc b/selfdrive/ui/qt/offroad/wifiManager.cc index f0ca79a06..cd3bdbd29 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.cc +++ b/selfdrive/ui/qt/offroad/wifiManager.cc @@ -6,6 +6,7 @@ #include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" +#include "selfdrive/ui/qt/util.h" template T get_response(QDBusMessage response) { @@ -35,9 +36,8 @@ WifiManager::WifiManager(QWidget* parent) : QWidget(parent) { // Set tethering ssid as "weedle" + first 4 characters of a dongle id tethering_ssid = "weedle"; - std::string bytes = Params().get("DongleId"); - if (bytes.length() >= 4) { - tethering_ssid += "-" + QString::fromStdString(bytes.substr(0,4)); + if (auto dongle_id = getDongleId()) { + tethering_ssid += "-" + dongle_id->left(4); } adapter = getAdapter(); diff --git a/selfdrive/ui/qt/qt_window.h b/selfdrive/ui/qt/qt_window.h index d17b01462..89d0c8061 100644 --- a/selfdrive/ui/qt/qt_window.h +++ b/selfdrive/ui/qt/qt_window.h @@ -19,11 +19,12 @@ const QString ASSET_PATH = ":/"; const QString ASSET_PATH = "../assets/"; #endif -const int vwp_w = (Hardware::TICI() || (getenv("WIDE_UI") != NULL)) ? 2160 : 1920; +const bool WIDE_UI = Hardware::TICI() || getenv("WIDE_UI") != nullptr; +const int vwp_w = WIDE_UI ? 2160 : 1920; const int vwp_h = 1080; inline void setMainWindow(QWidget *w) { - const float scale = getenv("SCALE") != NULL ? std::stof(getenv("SCALE")) : 1.0; + const float scale = util::getenv("SCALE", 1.0f); w->setFixedSize(vwp_w*scale, vwp_h*scale); w->show(); diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index da226b412..cd2c9534d 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -2,9 +2,6 @@ #include -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/common/util.h" -#include "selfdrive/hardware/hw.h" #include "selfdrive/ui/qt/util.h" void Sidebar::drawMetric(QPainter &p, const QString &label, const QString &val, QColor c, int y) { @@ -41,9 +38,9 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { connect(this, &Sidebar::valueChanged, [=] { update(); }); + setAttribute(Qt::WA_OpaquePaintEvent); + setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding); setFixedWidth(300); - setMinimumHeight(vwp_h); - setStyleSheet("background-color: rgb(57, 57, 57);"); } void Sidebar::mouseReleaseEvent(QMouseEvent *event) { @@ -60,42 +57,31 @@ void Sidebar::updateState(const UIState &s) { int strength = (int)deviceState.getNetworkStrength(); setProperty("netStrength", strength > 0 ? strength + 1 : 0); + ItemStatus connectstatus; auto last_ping = deviceState.getLastAthenaPingTime(); if (last_ping == 0) { - if (params.getBool("PrimeRedirected")) { - setProperty("connectStr", "NO\nPRIME"); - setProperty("connectStatus", danger_color); - } else { - setProperty("connectStr", "CONNECT\nOFFLINE"); - setProperty("connectStatus", warning_color); - } + connectstatus = params.getBool("PrimeRedirected") ? ItemStatus{"NO\nPRIME", danger_color} : ItemStatus{"CONNECT\nOFFLINE", warning_color}; } else { - bool online = nanos_since_boot() - last_ping < 80e9; - setProperty("connectStr", (online ? "CONNECT\nONLINE" : "CONNECT\nERROR")); - setProperty("connectStatus", online ? good_color : danger_color); + connectstatus = nanos_since_boot() - last_ping < 80e9 ? ItemStatus{"CONNECT\nONLINE", good_color} : ItemStatus{"CONNECT\nERROR", danger_color}; } + setProperty("connectStatus", QVariant::fromValue(connectstatus)); - QColor tempStatus = danger_color; + QColor tempColor = danger_color; auto ts = deviceState.getThermalStatus(); if (ts == cereal::DeviceState::ThermalStatus::GREEN) { - tempStatus = good_color; + tempColor = good_color; } else if (ts == cereal::DeviceState::ThermalStatus::YELLOW) { - tempStatus = warning_color; + tempColor = warning_color; } - setProperty("tempStatus", tempStatus); - setProperty("tempVal", (int)deviceState.getAmbientTempC()); + setProperty("tempStatus", QVariant::fromValue(ItemStatus{QString("%1°C").arg((int)deviceState.getAmbientTempC()), tempColor})); - QString pandaStr = "VEHICLE\nONLINE"; - QColor pandaStatus = good_color; + ItemStatus pandaStatus = {"VEHICLE\nONLINE", good_color}; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { - pandaStatus = danger_color; - pandaStr = "NO\nPANDA"; + pandaStatus = {"NO\nPANDA", danger_color}; } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = warning_color; - pandaStr = "GPS\nSEARCHING"; + pandaStatus = {"GPS\nSEARCHING", warning_color}; } - setProperty("pandaStr", pandaStr); - setProperty("pandaStatus", pandaStatus); + setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); } void Sidebar::paintEvent(QPaintEvent *event) { @@ -103,6 +89,8 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.setPen(Qt::NoPen); p.setRenderHint(QPainter::Antialiasing); + p.fillRect(rect(), QColor(57, 57, 57)); + // static imgs p.setOpacity(0.65); p.drawImage(settings_btn.x(), settings_btn.y(), settings_img); @@ -124,7 +112,7 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.drawText(r, Qt::AlignCenter, net_type); // metrics - drawMetric(p, "TEMP", QString("%1°C").arg(temp_val), temp_status, 338); - drawMetric(p, panda_str, "", panda_status, 518); - drawMetric(p, connect_str, "", connect_status, 676); + drawMetric(p, "TEMP", temp_status.first, temp_status.second, 338); + drawMetric(p, panda_status.first, "", panda_status.second, 518); + drawMetric(p, connect_status.first, "", connect_status.second, 676); } diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 7cd04519a..8785cd919 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -6,14 +6,14 @@ #include "selfdrive/common/params.h" #include "selfdrive/ui/ui.h" +typedef QPair ItemStatus; +Q_DECLARE_METATYPE(ItemStatus); + class Sidebar : public QFrame { Q_OBJECT - Q_PROPERTY(QString connectStr MEMBER connect_str NOTIFY valueChanged); - Q_PROPERTY(QColor connectStatus MEMBER connect_status NOTIFY valueChanged); - Q_PROPERTY(QString pandaStr MEMBER panda_str NOTIFY valueChanged); - Q_PROPERTY(QColor pandaStatus MEMBER panda_status NOTIFY valueChanged); - Q_PROPERTY(int tempVal MEMBER temp_val NOTIFY valueChanged); - Q_PROPERTY(QColor tempStatus MEMBER temp_status NOTIFY valueChanged); + Q_PROPERTY(ItemStatus connectStatus MEMBER connect_status NOTIFY valueChanged); + Q_PROPERTY(ItemStatus pandaStatus MEMBER panda_status NOTIFY valueChanged); + Q_PROPERTY(ItemStatus tempStatus MEMBER temp_status NOTIFY valueChanged); Q_PROPERTY(QString netType MEMBER net_type NOTIFY valueChanged); Q_PROPERTY(int netStrength MEMBER net_strength NOTIFY valueChanged); @@ -30,8 +30,6 @@ public slots: protected: void paintEvent(QPaintEvent *event) override; void mouseReleaseEvent(QMouseEvent *event) override; - -private: void drawMetric(QPainter &p, const QString &label, const QString &val, QColor c, int y); QImage home_img, settings_img; @@ -51,12 +49,7 @@ private: const QColor danger_color = QColor(201, 34, 49); Params params; - QString connect_str = "OFFLINE"; - QColor connect_status = warning_color; - QString panda_str = "NO\nPANDA"; - QColor panda_status = warning_color; - int temp_val = 0; - QColor temp_status = warning_color; + ItemStatus connect_status, panda_status, temp_status; QString net_type; int net_strength = 0; }; diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc index 5323d182a..8948d2adb 100644 --- a/selfdrive/ui/qt/spinner.cc +++ b/selfdrive/ui/qt/spinner.cc @@ -15,20 +15,24 @@ #include "selfdrive/ui/qt/util.h" TrackWidget::TrackWidget(QWidget *parent) : QWidget(parent) { + setAttribute(Qt::WA_OpaquePaintEvent); setFixedSize(spinner_size); - setAutoFillBackground(true); - setPalette(Qt::black); // pre-compute all the track imgs. make this a gif instead? QPixmap comma_img = QPixmap("../assets/img_spinner_comma.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); - QTransform transform(1, 0, 0, 1, width() / 2, height() / 2); QPixmap track_img = QPixmap("../assets/img_spinner_track.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); - for (QPixmap &img : track_imgs) { - img = comma_img; - QPainter p(&img); - p.setRenderHint(QPainter::SmoothPixmapTransform); + + QTransform transform(1, 0, 0, 1, width() / 2, height() / 2); + QPixmap pm(spinner_size); + QPainter p(&pm); + p.setRenderHint(QPainter::SmoothPixmapTransform); + for (int i = 0; i < track_imgs.size(); ++i) { + p.resetTransform(); + p.fillRect(0, 0, spinner_size.width(), spinner_size.height(), Qt::black); + p.drawPixmap(0, 0, comma_img); p.setTransform(transform.rotate(360 / spinner_fps)); p.drawPixmap(-width() / 2, -height() / 2, track_img); + track_imgs[i] = pm.copy(); } m_anim.setDuration(1000); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 1091624ac..3f98283bf 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -16,6 +16,16 @@ QString getBrandVersion() { return getBrand() + " v" + QString::fromStdString(Params().get("Version")).left(14).trimmed(); } +std::optional getDongleId() { + std::string id = Params().get("DongleId"); + + if (!id.empty() && (id != "UnregisteredDevice")) { + return QString::fromStdString(id); + } else { + return {}; + } +} + void configFont(QPainter &p, const QString &family, int size, const QString &style) { QFont f(family); f.setPixelSize(size); @@ -95,12 +105,12 @@ void ClickableWidget::paintEvent(QPaintEvent *) { void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { static std::map levels = { - {QtMsgType::QtDebugMsg, 10}, - {QtMsgType::QtInfoMsg, 20}, - {QtMsgType::QtWarningMsg, 30}, - {QtMsgType::QtCriticalMsg, 40}, - {QtMsgType::QtSystemMsg, 40}, - {QtMsgType::QtFatalMsg, 50}, + {QtMsgType::QtDebugMsg, CLOUDLOG_DEBUG}, + {QtMsgType::QtInfoMsg, CLOUDLOG_INFO}, + {QtMsgType::QtWarningMsg, CLOUDLOG_WARNING}, + {QtMsgType::QtCriticalMsg, CLOUDLOG_ERROR}, + {QtMsgType::QtSystemMsg, CLOUDLOG_ERROR}, + {QtMsgType::QtFatalMsg, CLOUDLOG_CRITICAL}, }; std::string file, function; diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 4928eae22..1c4e4b5f4 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -1,5 +1,7 @@ #pragma once +#include + #include #include #include @@ -9,6 +11,7 @@ QString getBrand(); QString getBrandVersion(); +std::optional getDongleId(); void configFont(QPainter &p, const QString &family, int size, const QString &style); void clearLayout(QLayout* layout); void setQtSurfaceFormat(); diff --git a/selfdrive/ui/qt/widgets/drive_stats.cc b/selfdrive/ui/qt/widgets/drive_stats.cc index 573e9b044..57c0794a2 100644 --- a/selfdrive/ui/qt/widgets/drive_stats.cc +++ b/selfdrive/ui/qt/widgets/drive_stats.cc @@ -7,6 +7,7 @@ #include "selfdrive/common/params.h" #include "selfdrive/ui/qt/request_repeater.h" +#include "selfdrive/ui/qt/util.h" const double MILE_TO_KM = 1.60934; @@ -46,10 +47,9 @@ DriveStats::DriveStats(QWidget* parent) : QFrame(parent) { main_layout->addStretch(); add_stats_layouts("PAST WEEK", week_); - std::string dongle_id = Params().get("DongleId"); - if (util::is_valid_dongle_id(dongle_id)) { - std::string url = "https://api.commadotai.com/v1.1/devices/" + dongle_id + "/stats"; - RequestRepeater* repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_DriveStats", 30); + if (auto dongleId = getDongleId()) { + QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/stats"; + RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_DriveStats", 30); QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &DriveStats::parseResponse); } diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index a27e6aaa3..e3828f3d8 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -11,6 +11,7 @@ #include #include "selfdrive/ui/qt/request_repeater.h" +#include "selfdrive/ui/qt/util.h" using qrcodegen::QrCode; @@ -109,10 +110,9 @@ PrimeUserWidget::PrimeUserWidget(QWidget* parent) : QWidget(parent) { mainLayout->addStretch(); // set up API requests - std::string dongleId = Params().get("DongleId"); - if (util::is_valid_dongle_id(dongleId)) { - std::string url = "https://api.commadotai.com/v1/devices/" + dongleId + "/owner"; - RequestRepeater *repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_Owner", 6); + if (auto dongleId = getDongleId()) { + QString url = CommaApi::BASE_URL + "/v1/devices/" + *dongleId + "/owner"; + RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_Owner", 6); QObject::connect(repeater, &RequestRepeater::receivedResponse, this, &PrimeUserWidget::replyFinished); } } @@ -255,10 +255,9 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { setSizePolicy(sp_retain); // set up API requests - std::string dongleId = Params().get("DongleId"); - if (util::is_valid_dongle_id(dongleId)) { - std::string url = "https://api.commadotai.com/v1.1/devices/" + dongleId + "/"; - RequestRepeater* repeater = new RequestRepeater(this, QString::fromStdString(url), "ApiCache_Device", 5); + 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::receivedResponse, this, &SetupWidget::replyFinished); QObject::connect(repeater, &RequestRepeater::failedResponse, this, &SetupWidget::parseError); diff --git a/selfdrive/ui/soundd b/selfdrive/ui/soundd index e658062b7..7517a1112 100755 --- a/selfdrive/ui/soundd +++ b/selfdrive/ui/soundd @@ -1,3 +1,4 @@ #!/bin/sh +cd "$(dirname "$0")" export LD_LIBRARY_PATH="/system/lib64:$LD_LIBRARY_PATH" exec ./_soundd diff --git a/selfdrive/ui/ui b/selfdrive/ui/ui index 064528749..36341a7ee 100755 --- a/selfdrive/ui/ui +++ b/selfdrive/ui/ui @@ -1,4 +1,5 @@ #!/bin/sh +cd "$(dirname "$0")" export LD_LIBRARY_PATH="/system/lib64:$LD_LIBRARY_PATH" export QT_PLUGIN_PATH="../../phonelibs/qt-plugins/$(uname -m)" exec ./_ui diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index bb0c0c85a..f6fbb495e 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -63,13 +63,13 @@ static int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line return max_idx; } -static void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, std::optional line) { +static void update_leads(UIState *s, const cereal::ModelDataV2::Reader &model) { + auto leads = model.getLeadsV3(); + auto model_position = model.getPosition(); 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 ? (*line).getZ()[get_path_length_idx(*line, lead_data.getDRel())] : 0.0; - // negative because radarState uses left positive convention - calib_frame_to_full_frame(s, lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &s->scene.lead_vertices[i]); + if (leads[i].getProb() > 0.5) { + float z = model_position.getZ()[get_path_length_idx(model_position, leads[i].getX()[0])]; + calib_frame_to_full_frame(s, leads[i].getX()[0], leads[i].getY()[0], z + 1.22, &s->scene.lead_vertices[i]); } } } @@ -112,9 +112,9 @@ static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) { } // update path - auto lead_one = (*s->sm)["radarState"].getRadarState().getLeadOne(); - if (lead_one.getStatus()) { - const float lead_d = lead_one.getDRel() * 2.; + auto lead_one = model.getLeadsV3()[0]; + if (lead_one.getProb() > 0.5) { + const float lead_d = lead_one.getX()[0] * 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); @@ -134,12 +134,10 @@ static void update_state(UIState *s) { scene.engageable = sm["controlsState"].getControlsState().getEngageable(); scene.dm_active = sm["driverMonitoringState"].getDriverMonitoringState().getIsActiveMode(); } - if (sm.updated("radarState") && s->vg) { - std::optional line; - if (sm.rcv_frame("modelV2") > 0) { - line = sm["modelV2"].getModelV2().getPosition(); - } - update_leads(s, sm["radarState"].getRadarState(), line); + if (sm.updated("modelV2") && s->vg) { + auto model = sm["modelV2"].getModelV2(); + update_model(s, model); + update_leads(s, model); } if (sm.updated("liveCalibration")) { scene.world_objects_visible = true; @@ -158,9 +156,6 @@ static void update_state(UIState *s) { } } } - if (sm.updated("modelV2") && s->vg) { - update_model(s, sm["modelV2"].getModelV2()); - } if (sm.updated("pandaState")) { auto pandaState = sm["pandaState"].getPandaState(); scene.pandaType = pandaState.getPandaType(); @@ -189,15 +184,17 @@ static void update_state(UIState *s) { if (sm.updated("roadCameraState")) { auto camera_state = sm["roadCameraState"].getRoadCameraState(); - float max_lines = Hardware::EON() ? 5408 : 1757; - float gain = camera_state.getGain(); + float max_lines = Hardware::EON() ? 5408 : 1904; + float max_gain = Hardware::EON() ? 1.0: 10.0; + float max_ev = max_lines * max_gain; - if (Hardware::TICI()) { - // Max gain is 4 * 2.5 (High Conversion Gain) - gain /= 10.0; + if (Hardware::TICI) { + max_ev /= 6; } - scene.light_sensor = std::clamp((1023.0 / max_lines) * (max_lines - camera_state.getIntegLines() * gain), 0.0, 1023.0); + float ev = camera_state.getGain() * float(camera_state.getIntegLines()); + + scene.light_sensor = std::clamp(1.0 - (ev / max_ev), 0.0, 1.0); } scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; } @@ -273,7 +270,7 @@ static void update_status(UIState *s) { QUIState::QUIState(QObject *parent) : QObject(parent) { ui_state.sm = std::make_unique>({ - "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", + "modelV2", "controlsState", "liveCalibration", "deviceState", "roadCameraState", "pandaState", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", }); @@ -305,7 +302,7 @@ void QUIState::update() { started_prev = ui_state.scene.started; emit offroadTransition(!ui_state.scene.started); - // Change timeout to 0 when onroad, this will call update continously. + // Change timeout to 0 when onroad, this will call update continuously. // This puts visionIPC in charge of update frequency, reducing video latency timer->start(ui_state.scene.started ? 0 : 1000 / UI_FREQ); } @@ -339,9 +336,19 @@ void Device::setAwake(bool on, bool reset) { } void Device::updateBrightness(const UIState &s) { - float brightness_b = 10; - float brightness_m = 0.1; - float clipped_brightness = std::min(100.0f, (s.scene.light_sensor * brightness_m) + brightness_b); + // Scale to 0% to 100% + float clipped_brightness = 100.0 * s.scene.light_sensor; + + // CIE 1931 - https://www.photonstophotos.net/GeneralTopics/Exposure/Psychometric_Lightness_and_Gamma.htm + if (clipped_brightness <= 8) { + clipped_brightness = (clipped_brightness / 903.3); + } else { + clipped_brightness = std::pow((clipped_brightness + 16.0) / 116.0, 3.0); + } + + // Scale back to 10% to 100% + clipped_brightness = std::clamp(100.0f * clipped_brightness, 10.0f, 100.0f); + if (!s.scene.started) { clipped_brightness = BACKLIGHT_OFFROAD; }