From a40cfb9d003fa95383aeebfa3be2452324225de8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 6 Jun 2018 20:52:02 +0100 Subject: [PATCH 001/110] Initial USB MSC support from Betaflight Code by @conkerh, @jflyper and @mikeller Only F4 and F7 are supported, since this feature takes ~9K of flash and F3 only has ~15K free right now. Use the new 'msc' CLI command to enable MSC mode. The FC will reboot as a USB mass storage device. To exit the mode, just power cycle. --- make/mcu/STM32F4.mk | 42 +- make/mcu/STM32F7.mk | 42 +- make/source.mk | 10 +- src/main/drivers/sdmmc_sdio.h | 241 ++++++++++ src/main/drivers/usb_msc.h | 33 ++ src/main/drivers/usb_msc_f4xx.c | 159 +++++++ src/main/drivers/usb_msc_f7xx.c | 157 ++++++ src/main/fc/cli.c | 40 ++ src/main/fc/fc_init.c | 17 + src/main/msc/emfat.c | 735 +++++++++++++++++++++++++++++ src/main/msc/emfat.h | 113 +++++ src/main/msc/emfat_file.c | 334 +++++++++++++ src/main/msc/emfat_file.h | 23 + src/main/msc/usbd_msc_desc.c | 383 +++++++++++++++ src/main/msc/usbd_msc_desc.h | 132 ++++++ src/main/msc/usbd_storage.c | 38 ++ src/main/msc/usbd_storage.h | 46 ++ src/main/msc/usbd_storage_emfat.c | 154 ++++++ src/main/msc/usbd_storage_emfat.h | 25 + src/main/msc/usbd_storage_sd_spi.c | 257 ++++++++++ src/main/msc/usbd_storage_sdio.c | 285 +++++++++++ src/main/target/common.h | 5 + src/main/vcp_hal/usbd_conf.h | 3 +- src/main/vcp_hal/usbd_desc.c | 34 ++ src/main/vcpf4/usbd_conf.h | 23 +- src/main/vcpf4/usbd_desc.h | 15 + 26 files changed, 3337 insertions(+), 9 deletions(-) create mode 100644 src/main/drivers/sdmmc_sdio.h create mode 100644 src/main/drivers/usb_msc.h create mode 100644 src/main/drivers/usb_msc_f4xx.c create mode 100644 src/main/drivers/usb_msc_f7xx.c create mode 100644 src/main/msc/emfat.c create mode 100644 src/main/msc/emfat.h create mode 100644 src/main/msc/emfat_file.c create mode 100644 src/main/msc/emfat_file.h create mode 100644 src/main/msc/usbd_msc_desc.c create mode 100644 src/main/msc/usbd_msc_desc.h create mode 100644 src/main/msc/usbd_storage.c create mode 100644 src/main/msc/usbd_storage.h create mode 100644 src/main/msc/usbd_storage_emfat.c create mode 100644 src/main/msc/usbd_storage_emfat.h create mode 100644 src/main/msc/usbd_storage_sd_spi.c create mode 100644 src/main/msc/usbd_storage_sdio.c diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk index 09fe494405e..0a4da28a323 100644 --- a/make/mcu/STM32F4.mk +++ b/make/mcu/STM32F4.mk @@ -84,12 +84,23 @@ USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c)) EXCLUDES = usbd_cdc_if_template.c USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) -VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src +USBMSC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/msc +USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/src/*.c)) +EXCLUDES = usbd_storage_template.c +USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC)) +USBHID_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid +USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/src/*.c)) +USBWRAPPER_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper +USBWRAPPER_SRC = $(notdir $(wildcard $(USBWRAPPER_DIR)/src/*.c)) +VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src:$(USBMSC_DIR)/src:$(USBHID_DIR)/src:$(USBWRAPPER_DIR)/src DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ $(USBOTG_SRC) \ $(USBCORE_SRC) \ - $(USBCDC_SRC) + $(USBCDC_SRC) \ + $(USBHID_SRC) \ + $(USBWRAPPER_SRC) \ + $(USBMSC_SRC) endif #CMSIS @@ -112,6 +123,9 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(USBOTG_DIR)/inc \ $(USBCORE_DIR)/inc \ $(USBCDC_DIR)/inc \ + $(USBHID_DIR)/inc \ + $(USBWRAPPER_DIR)/inc \ + $(USBMSC_DIR)/inc \ $(USBFS_DIR)/inc \ $(CMSIS_DIR)/Core/Include \ $(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx \ @@ -183,6 +197,30 @@ VCP_SRC = \ drivers/usb_io.c endif +MSC_SRC = \ + drivers/usb_msc_f4xx.c \ + msc/usbd_msc_desc.c \ + msc/usbd_storage.c + +ifneq ($(filter SDCARD,$(FEATURES)),) +MSC_SRC += \ + msc/usbd_storage_sd_spi.c +endif + +ifneq ($(filter SDIO,$(FEATURES)),) +MSC_SRC += \ + msc/usbd_storage_sdio.c +MCU_COMMON_SRC += \ + drivers/sdio_f4xx.c +endif + +ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) +MSC_SRC += \ + msc/usbd_storage_emfat.c \ + msc/emfat.c \ + msc/emfat_file.c +endif + DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index e2139a7c815..1980573d378 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -78,12 +78,25 @@ USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c)) EXCLUDES = usbd_cdc_if_template.c USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) -VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src +USBHID_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID +USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c)) + +USBHIDCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID +USBHIDCDC_SRC = $(notdir $(wildcard $(USBHIDCDC_DIR)/Src/*.c)) + +USBMSC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC +USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c)) +EXCLUDES = usbd_msc_storage_template.c +USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC)) + +VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBHIDCDC_DIR)/Src:$(USBMSC_DIR)/Src DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ $(USBCORE_SRC) \ $(USBCDC_SRC) \ - $(USBHID_SRC) + $(USBHID_SRC) \ + $(USBHIDCDC_SRC) \ + $(USBMSC_SRC) #CMSIS VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx @@ -94,6 +107,8 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(USBCORE_DIR)/Inc \ $(USBCDC_DIR)/Inc \ $(USBHID_DIR)/Inc \ + $(USBHIDCDC_DIR)/Inc \ + $(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ $(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \ $(ROOT)/src/main/vcp_hal @@ -161,5 +176,28 @@ MCU_EXCLUDES = \ drivers/bus_i2c.c \ drivers/serial_uart.c +MSC_SRC = \ + drivers/usb_msc_f7xx.c \ + msc/usbd_storage.c + +ifneq ($(filter SDIO,$(FEATURES)),) +MCU_COMMON_SRC += \ + drivers/sdio_f7xx.c +MSC_SRC += \ + msc/usbd_storage_sdio.c +endif + +ifneq ($(filter SDCARD,$(FEATURES)),) +MSC_SRC += \ + msc/usbd_storage_sd_spi.c +endif + +ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) +MSC_SRC += \ + msc/usbd_storage_emfat.c \ + msc/emfat.c \ + msc/emfat_file.c +endif + DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7 diff --git a/make/source.mk b/make/source.mk index e1a76eea0ff..b53535f349e 100644 --- a/make/source.mk +++ b/make/source.mk @@ -194,7 +194,8 @@ TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC)) ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) TARGET_SRC += \ drivers/flash_m25p16.c \ - io/flashfs.c + io/flashfs.c \ + $(MSC_SRC) endif ifneq ($(filter SDCARD,$(FEATURES)),) @@ -202,12 +203,17 @@ TARGET_SRC += \ drivers/sdcard.c \ drivers/sdcard_standard.c \ io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c + io/asyncfatfs/fat_standard.c \ + $(MSC_SRC) endif ifneq ($(filter VCP,$(FEATURES)),) TARGET_SRC += $(VCP_SRC) endif +ifneq ($(filter MSC,$(FEATURES)),) +SRC += $(MSC_SRC) +endif + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/src/main/drivers/sdmmc_sdio.h b/src/main/drivers/sdmmc_sdio.h new file mode 100644 index 00000000000..075768189dd --- /dev/null +++ b/src/main/drivers/sdmmc_sdio.h @@ -0,0 +1,241 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Original author: Alain (https://github.com/aroyer-qc) + * Modified for F4 and BF source: Chris Hockuba (https://github.com/conkerkh) + * + */ + +#ifndef __fatfs_sd_sdio_H__ +#define __fatfs_sd_sdio_H__ + +#include + +#include "platform.h" +#ifdef STM32F4 +#include "stm32f4xx.h" +#endif + +#ifdef STM32F7 +#include "stm32f7xx.h" +#endif + + /* SDCARD pinouts + * + * SD CARD PINS + _________________ + / 1 2 3 4 5 6 7 8 | NR |SDIO INTERFACE + / | |NAME STM32F746 DESCRIPTION +/ 9 | | 4-BIT 1-BIT +| | | +| | 1 |CD/DAT3 PC11 - Connector data line 3 +| | 2 |CMD PD2 PD2 Command/Response line +| | 3 |VSS1 GND GND GND +| SD CARD Pinout | 4 |VDD 3.3V 3.3V 3.3V Power supply +| | 5 |CLK PC12 PC12 Clock +| | 6 |VSS2 GND GND GND +| | 7 |DAT0 PC8 PC8 Connector data line 0 +| | 8 |DAT1 PC9 - Connector data line 1 +|___________________| 9 |DAT2 PC10 - Connector data line 2 + + */ + +/* Define(s) --------------------------------------------------------------------------------------------------------*/ + +//#define MSD_OK ((uint8_t)0x00) +#define MSD_ERROR ((uint8_t)0x01) +#define MSD_ERROR_SD_NOT_PRESENT ((uint8_t)0x02) + +#define SD_PRESENT ((uint8_t)0x01) +#define SD_NOT_PRESENT ((uint8_t)0x00) + +#define SD_DATATIMEOUT ((uint32_t)100000000) + +#define SD_DETECT_GPIO_PORT GPIOC +#define SD_DETECT_PIN GPIO_PIN_13 + +/* Structure(s) -----------------------------------------------------------------------------------------------------*/ + +typedef enum +{ + // SD specific error defines + SD_CMD_CRC_FAIL = (1), // Command response received (but CRC check failed) + SD_DATA_CRC_FAIL = (2), // Data block sent/received (CRC check failed) + SD_CMD_RSP_TIMEOUT = (3), // Command response TimeOut + SD_DATA_TIMEOUT = (4), // Data TimeOut + SD_TX_UNDERRUN = (5), // Transmit FIFO underrun + SD_RX_OVERRUN = (6), // Receive FIFO overrun + SD_START_BIT_ERR = (7), // Start bit not detected on all data signals in wide bus mode + SD_CMD_OUT_OF_RANGE = (8), // Command's argument was out of range. + SD_ADDR_MISALIGNED = (9), // Misaligned address + SD_BLOCK_LEN_ERR = (10), // Transferred block length is not allowed for the card or the number of transferred bytes does not match the block length + SD_ERASE_SEQ_ERR = (11), // An error in the sequence of erase command occurs. + SD_BAD_ERASE_PARAM = (12), // An invalid selection for erase groups + SD_WRITE_PROT_VIOLATION = (13), // Attempt to program a write protect block + SD_LOCK_UNLOCK_FAILED = (14), // Sequence or password error has been detected in unlock command or if there was an attempt to access a locked card + SD_COM_CRC_FAILED = (15), // CRC check of the previous command failed + SD_ILLEGAL_CMD = (16), // Command is not legal for the card state + SD_CARD_ECC_FAILED = (17), // Card internal ECC was applied but failed to correct the data + SD_CC_ERROR = (18), // Internal card controller error + SD_GENERAL_UNKNOWN_ERROR = (19), // General or unknown error + SD_STREAM_READ_UNDERRUN = (20), // The card could not sustain data transfer in stream read operation. + SD_STREAM_WRITE_OVERRUN = (21), // The card could not sustain data programming in stream mode + SD_CID_CSD_OVERWRITE = (22), // CID/CSD overwrite error + SD_WP_ERASE_SKIP = (23), // Only partial address space was erased + SD_CARD_ECC_DISABLED = (24), // Command has been executed without using internal ECC + SD_ERASE_RESET = (25), // Erase sequence was cleared before executing because an out of erase sequence command was received + SD_AKE_SEQ_ERROR = (26), // Error in sequence of authentication. + SD_INVALID_VOLTRANGE = (27), + SD_ADDR_OUT_OF_RANGE = (28), + SD_SWITCH_ERROR = (29), + SD_SDMMC_DISABLED = (30), + SD_SDMMC_FUNCTION_BUSY = (31), + SD_SDMMC_FUNCTION_FAILED = (32), + SD_SDMMC_UNKNOWN_FUNCTION = (33), + SD_OUT_OF_BOUND = (34), + + + // Standard error defines + SD_INTERNAL_ERROR = (35), + SD_NOT_CONFIGURED = (36), + SD_REQUEST_PENDING = (37), + SD_REQUEST_NOT_APPLICABLE = (38), + SD_INVALID_PARAMETER = (39), + SD_UNSUPPORTED_FEATURE = (40), + SD_UNSUPPORTED_HW = (41), + SD_ERROR = (42), + SD_BUSY = (43), + SD_OK = (0) +} SD_Error_t; + + +typedef struct +{ + uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width + uint8_t SECURED_MODE; // Card is in secured mode of operation + uint16_t SD_CARD_TYPE; // Carries information about card type + uint32_t SIZE_OF_PROTECTED_AREA; // Carries information about the capacity of protected area + uint8_t SPEED_CLASS; // Carries information about the speed class of the card + uint8_t PERFORMANCE_MOVE; // Carries information about the card's performance move + uint8_t AU_SIZE; // Carries information about the card's allocation unit size + uint16_t ERASE_SIZE; // Determines the number of AUs to be erased in one operation + uint8_t ERASE_TIMEOUT; // Determines the TimeOut for any number of AU erase + uint8_t ERASE_OFFSET; // Carries information about the erase offset +} SD_CardStatus_t; + +typedef struct +{ + uint8_t CSDStruct; // CSD structure + uint8_t SysSpecVersion; // System specification version + uint8_t Reserved1; // Reserved + uint8_t TAAC; // Data read access time 1 + uint8_t NSAC; // Data read access time 2 in CLK cycles + uint8_t MaxBusClkFrec; // Max. bus clock frequency + uint16_t CardComdClasses; // Card command classes + uint8_t RdBlockLen; // Max. read data block length + uint8_t PartBlockRead; // Partial blocks for read allowed + uint8_t WrBlockMisalign; // Write block misalignment + uint8_t RdBlockMisalign; // Read block misalignment + uint8_t DSRImpl; // DSR implemented + uint8_t Reserved2; // Reserved + uint32_t DeviceSize; // Device Size + uint8_t MaxRdCurrentVDDMin; // Max. read current @ VDD min + uint8_t MaxRdCurrentVDDMax; // Max. read current @ VDD max + uint8_t MaxWrCurrentVDDMin; // Max. write current @ VDD min + uint8_t MaxWrCurrentVDDMax; // Max. write current @ VDD max + uint8_t DeviceSizeMul; // Device size multiplier + uint8_t EraseGrSize; // Erase group size + uint8_t EraseGrMul; // Erase group size multiplier + uint8_t WrProtectGrSize; // Write protect group size + uint8_t WrProtectGrEnable; // Write protect group enable + uint8_t ManDeflECC; // Manufacturer default ECC + uint8_t WrSpeedFact; // Write speed factor + uint8_t MaxWrBlockLen; // Max. write data block length + uint8_t WriteBlockPaPartial; // Partial blocks for write allowed + uint8_t Reserved3; // Reserved + uint8_t ContentProtectAppli; // Content protection application + uint8_t FileFormatGrouop; // File format group + uint8_t CopyFlag; // Copy flag (OTP) + uint8_t PermWrProtect; // Permanent write protection + uint8_t TempWrProtect; // Temporary write protection + uint8_t FileFormat; // File format + uint8_t ECC; // ECC code + uint8_t CSD_CRC; // CSD CRC + uint8_t Reserved4; // Always 1 +} SD_CSD_t; + +typedef struct +{ + uint8_t ManufacturerID; // Manufacturer ID + uint16_t OEM_AppliID; // OEM/Application ID + uint32_t ProdName1; // Product Name part1 + uint8_t ProdName2; // Product Name part2 + uint8_t ProdRev; // Product Revision + uint32_t ProdSN; // Product Serial Number + uint8_t Reserved1; // Reserved1 + uint16_t ManufactDate; // Manufacturing Date + uint8_t CID_CRC; // CID CRC + uint8_t Reserved2; // Always 1 + +} SD_CID_t; + +typedef enum +{ + SD_STD_CAPACITY_V1_1 = 0, + SD_STD_CAPACITY_V2_0 = 1, + SD_HIGH_CAPACITY = 2, + SD_MULTIMEDIA = 3, + SD_SECURE_DIGITAL_IO = 4, + SD_HIGH_SPEED_MULTIMEDIA = 5, + SD_SECURE_DIGITAL_IO_COMBO = 6, + SD_HIGH_CAPACITY_MMC = 7, +} SD_CardType_t; + +typedef struct +{ + volatile SD_CSD_t SD_csd; // SD card specific data register + volatile SD_CID_t SD_cid; // SD card identification number register + uint64_t CardCapacity; // Card capacity + uint32_t CardBlockSize; // Card block size +} SD_CardInfo_t; + +/* Prototype(s) -----------------------------------------------------------------------------------------------------*/ + +extern SD_CardInfo_t SD_CardInfo; +extern SD_CardType_t SD_CardType; + +void SD_Initialize_LL (DMA_Stream_TypeDef *dma); +bool SD_Init (void); +bool SD_IsDetected (void); +bool SD_GetState (void); +SD_Error_t SD_GetCardInfo (void); + +SD_Error_t SD_ReadBlocks_DMA (uint64_t ReadAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks); +SD_Error_t SD_CheckRead (void); +SD_Error_t SD_WriteBlocks_DMA (uint64_t WriteAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks); +SD_Error_t SD_CheckWrite (void); + +SD_Error_t SD_Erase (uint64_t StartAddress, uint64_t EndAddress); +SD_Error_t SD_GetCardStatus (SD_CardStatus_t* pCardStatus); + +/* ------------------------------------------------------------------------------------------------------------------*/ + +#endif // __fatfs_sd_sdio_H__ diff --git a/src/main/drivers/usb_msc.h b/src/main/drivers/usb_msc.h new file mode 100644 index 00000000000..3995b3c170b --- /dev/null +++ b/src/main/drivers/usb_msc.h @@ -0,0 +1,33 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: Chris Hockuba (https://github.com/conkerkh) + */ + +#pragma once + +#define MSC_MAGIC 0xDDDD1010 + +void mscInit(void); +bool mscCheckBoot(void); +uint8_t mscStart(void); +bool mscCheckButton(void); +void mscWaitForButton(void); diff --git a/src/main/drivers/usb_msc_f4xx.c b/src/main/drivers/usb_msc_f4xx.c new file mode 100644 index 00000000000..2b9a7f847b8 --- /dev/null +++ b/src/main/drivers/usb_msc_f4xx.c @@ -0,0 +1,159 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: Chris Hockuba (https://github.com/conkerkh) + * + */ + +#include +#include +#include + +#include "platform.h" + +#if defined(USE_USB_MSC) + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "blackbox/blackbox.h" +#include "blackbox/blackbox_io.h" + +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/nvic.h" +#include "drivers/sdmmc_sdio.h" +#include "drivers/time.h" +#include "drivers/usb_msc.h" + +#if defined(STM32F4) +#include "usb_core.h" +#include "usbd_cdc_vcp.h" +#include "usb_io.h" +#elif defined(STM32F7) +#include "vcp_hal/usbd_cdc_interface.h" +#include "usb_io.h" +USBD_HandleTypeDef USBD_Device; +#else +#include "usb_core.h" +#include "usb_init.h" +#include "hw_config.h" +#endif + +#include "msc/usbd_storage.h" + +#define DEBOUNCE_TIME_MS 20 + +#if defined(MSC_USE_BUTTON) +static IO_t mscButton; +#endif + +void mscInit(void) +{ +#if defined(MSC_USE_BUTTON) + if (usbDevConfig()->mscButtonPin) { + mscButton = IOGetByTag(usbDevConfig()->mscButtonPin); + IOInit(mscButton, OWNER_USB_MSC_PIN, 0); + if (usbDevConfig()->mscButtonUsePullup) { + IOConfigGPIO(mscButton, IOCFG_IPU); + } else { + IOConfigGPIO(mscButton, IOCFG_IPD); + } + } +#endif +} + +uint8_t mscStart(void) +{ + ledInit(false); + + //Start USB + usbGenerateDisconnectPulse(); + + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0, 0); + + switch (blackboxConfig()->device) { +#ifdef USE_SDCARD + case BLACKBOX_DEVICE_SDCARD: + USBD_STORAGE_fops = &USBD_MSC_MICRO_SDIO_fops; + break; +#endif + +#ifdef USE_FLASHFS + case BLACKBOX_DEVICE_FLASH: + USBD_STORAGE_fops = &USBD_MSC_EMFAT_fops; + break; +#endif + default: + return 1; + } + + USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &MSC_desc, &USBD_MSC_cb, &USR_cb); + + // NVIC configuration for SYSTick + NVIC_DisableIRQ(SysTick_IRQn); + NVIC_SetPriority(SysTick_IRQn, NVIC_BUILD_PRIORITY(0, 0)); + NVIC_EnableIRQ(SysTick_IRQn); + + return 0; +} + +bool mscCheckBoot(void) +{ + if (*((uint32_t *)0x2001FFF0) == MSC_MAGIC) { + return true; + } + return false; +} + +bool mscCheckButton(void) +{ + bool result = false; +#if defined(MSC_USE_BUTTON) + if (mscButton) { + uint8_t state = IORead(mscButton); + if (usbDevConfig()->mscButtonUsePullup) { + result = state == 0; + } else { + result = state == 1; + } + } +#endif + return result; +} + +void mscWaitForButton(void) +{ + // In order to exit MSC mode simply disconnect the board, or push the button again. + while (mscCheckButton()); + delay(DEBOUNCE_TIME_MS); + while (true) { + asm("NOP"); + if (mscCheckButton()) { + *((uint32_t *)0x2001FFF0) = 0xFFFFFFFF; + delay(1); + NVIC_SystemReset(); + } + } +} +#endif diff --git a/src/main/drivers/usb_msc_f7xx.c b/src/main/drivers/usb_msc_f7xx.c new file mode 100644 index 00000000000..d688becfa6e --- /dev/null +++ b/src/main/drivers/usb_msc_f7xx.c @@ -0,0 +1,157 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: Chris Hockuba (https://github.com/conkerkh) + * + */ + +#include +#include +#include + +#include "platform.h" + +#if defined(USE_USB_MSC) + +#include "build/build_config.h" + +#include "blackbox/blackbox.h" +#include "blackbox/blackbox_io.h" + +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/nvic.h" +#include "drivers/time.h" +#include "drivers/usb_msc.h" + +#include "vcp_hal/usbd_cdc_interface.h" +#include "usb_io.h" +#include "usbd_msc.h" +#include "msc/usbd_storage.h" + +USBD_HandleTypeDef USBD_Device; + +#define DEBOUNCE_TIME_MS 20 + +#if defined(MSC_USE_BUTTON) +static IO_t mscButton; +#endif + +void mscInit(void) +{ +#if defined(MSC_USE_BUTTON) + if (usbDevConfig()->mscButtonPin) { + mscButton = IOGetByTag(usbDevConfig()->mscButtonPin); + IOInit(mscButton, OWNER_USB_MSC_PIN, 0); + if (usbDevConfig()->mscButtonUsePullup) { + IOConfigGPIO(mscButton, IOCFG_IPU); + } else { + IOConfigGPIO(mscButton, IOCFG_IPD); + } + } +#endif +} + +uint8_t mscStart(void) +{ + ledInit(false); + + //Start USB + usbGenerateDisconnectPulse(); + + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0, 0); + + USBD_Init(&USBD_Device, &VCP_Desc, 0); + + /** Regsiter class */ + USBD_RegisterClass(&USBD_Device, USBD_MSC_CLASS); + + /** Register interface callbacks */ + switch (blackboxConfig()->device) { +#ifdef USE_SDCARD + case BLACKBOX_DEVICE_SDCARD: + USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_MICRO_SDIO_fops); + break; +#endif + +#ifdef USE_FLASHFS + case BLACKBOX_DEVICE_FLASH: + USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_EMFAT_fops); + break; +#endif + + default: + return 1; + } + + USBD_Start(&USBD_Device); + + // NVIC configuration for SYSTick + NVIC_DisableIRQ(SysTick_IRQn); + NVIC_SetPriority(SysTick_IRQn, NVIC_BUILD_PRIORITY(0, 0)); + NVIC_EnableIRQ(SysTick_IRQn); + + return 0; +} + +bool mscCheckBoot(void) +{ + if (*((__IO uint32_t *)BKPSRAM_BASE + 16) == MSC_MAGIC) { + return true; + } + return false; +} + +bool mscCheckButton(void) +{ + bool result = false; +#if defined(MSC_USE_BUTTON) + if (mscButton) { + uint8_t state = IORead(mscButton); + if (usbDevConfig()->mscButtonUsePullup) { + result = state == 0; + } else { + result = state == 1; + } + } +#endif + + return result; +} + +void mscWaitForButton(void) +{ + // In order to exit MSC mode simply disconnect the board, or push the button again. + while (mscCheckButton()); + delay(DEBOUNCE_TIME_MS); + while (true) { + asm("NOP"); + if (mscCheckButton()) { + *((uint32_t *)0x2001FFF0) = 0xFFFFFFFF; + delay(1); + NVIC_SystemReset(); + } + } +} +#endif diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index f6f079272c0..5ddbc56388f 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -64,6 +64,7 @@ extern uint8_t __config_end; #include "drivers/system.h" #include "drivers/time.h" #include "drivers/timer.h" +#include "drivers/usb_msc.h" #include "fc/cli.h" #include "fc/config.h" @@ -2712,6 +2713,42 @@ static void cliDiff(char *cmdline) printConfig(cmdline, true); } +#ifdef USE_USB_MSC +static void cliMsc(char *cmdline) +{ + UNUSED(cmdline); + + if (false +#ifdef USE_SDCARD + || sdcard_isFunctional() +#endif +#ifdef USE_FLASHFS + || flashfsGetSize() > 0 +#endif + ) { + cliPrintHashLine("restarting in mass storage mode"); + cliPrint("\r\nRebooting"); + bufWriterFlush(cliWriter); + delay(1000); + waitForSerialPortToFinishTransmitting(cliPort); + stopPwmAllMotors(); + +#ifdef STM32F7 + *((__IO uint32_t*) BKPSRAM_BASE + 16) = MSC_MAGIC; +#elif defined(STM32F4) + *((uint32_t *)0x2001FFF0) = MSC_MAGIC; +#endif + + __disable_irq(); + NVIC_SystemReset(); + } else { + cliPrint("\r\nStorage not present or failed to initialize!"); + bufWriterFlush(cliWriter); + } +} +#endif + + typedef struct { const char *name; #ifndef SKIP_CLI_COMMAND_HELP @@ -2790,6 +2827,9 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("memory", "view memory usage", NULL, cliMemory), CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix), CLI_COMMAND_DEF("motor", "get/set motor", " []", cliMotor), +#ifdef USE_USB_MSC + CLI_COMMAND_DEF("msc", "switch into msc mode", NULL, cliMsc), +#endif CLI_COMMAND_DEF("name", "name of craft", NULL, cliName), #ifdef PLAY_SOUND CLI_COMMAND_DEF("play_sound", NULL, "[]\r\n", cliPlaySound), diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index d195bb1296e..07c4231db04 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -75,6 +75,9 @@ #include "drivers/io_pca9685.h" #include "drivers/vtx_rtc6705.h" #include "drivers/vtx_common.h" +#ifdef USE_USB_MSC +#include "drivers/usb_msc.h" +#endif #include "fc/cli.h" #include "fc/config.h" @@ -420,6 +423,20 @@ void init(void) } #endif +#ifdef USE_USB_MSC + /* MSC mode will start after init, but will not allow scheduler to run, + * so there is no bottleneck in reading and writing data + */ + mscInit(); + if (mscCheckBoot() || mscCheckButton()) { + if (mscStart() == 0) { + mscWaitForButton(); + } else { + NVIC_SystemReset(); + } + } +#endif + #ifdef USE_I2C #ifdef USE_I2C_DEVICE_1 #ifdef I2C_DEVICE_1_SHARES_UART3 diff --git a/src/main/msc/emfat.c b/src/main/msc/emfat.c new file mode 100644 index 00000000000..bcf87ee5fec --- /dev/null +++ b/src/main/msc/emfat.c @@ -0,0 +1,735 @@ +/* + * Derived from + * https://github.com/fetisov/emfat/blob/master/project/emfat.c + * version: 1.1 (2.04.2017) + */ + +/* + * The MIT License (MIT) + * + * Copyright (c) 2015 by Sergey Fetisov + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#include "common/utils.h" + +#include "emfat.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define SECT 512 +#define CLUST 4096 +#define SECT_PER_CLUST (CLUST / SECT) +#define SIZE_TO_NSECT(s) ((s) == 0 ? 1 : ((s) + SECT - 1) / SECT) +#define SIZE_TO_NCLUST(s) ((s) == 0 ? 1 : ((s) + CLUST - 1) / CLUST) + +#define CLUST_FREE 0x00000000 +#define CLUST_RESERVED 0x00000001 +#define CLUST_BAD 0x0FFFFFF7 +#define CLUST_ROOT_END 0X0FFFFFF8 +#define CLUST_EOF 0x0FFFFFFF + +#define MAX_DIR_ENTRY_CNT 16 +#define FILE_SYS_TYPE_OFF 82 +#define BYTES_PER_SEC_OFF 11 +#define SEC_PER_CLUS_OFF 13 +#define RES_SEC_CNT_OFF 14 +#define FAT_CNT_OFF 16 +#define TOT_SEC_CNT_OFF 32 +#define SEC_PER_FAT 36 +#define ROOT_DIR_STRT_CLUS_OFF 44 +#define FS_INFOSECTOR_OFF 48 +#define BACKUP_BOOT_SEC_OFF 50 +#define NXT_FREE_CLUS_OFF 492 +#define FILE_SYS_TYPE_LENGTH 8 +#define SHRT_FILE_NAME_LEN 11 +#define STRT_CLUS_LOW_OFF 26 +#define STRT_CLUS_HIGH_OFF 20 +#define FILE_SIZE_OFF 28 +#define ATTR_OFF 11 +#define FILE_STAT_LEN 21 +#define CHECK_SUM_OFF 13 +#define FILE_NAME_SHRT_LEN 8 +#define FILE_NAME_EXTN_LEN 3 +#define LONG_FILE_NAME_LEN 255 +#define LOW_CLUSWORD_MASK 0x0000FFFF +#define HIGH_CLUSWORD_MASK 0xFFFF0000 +#define LONG_FNAME_MASK 0x0F +#define LAST_ORD_FIELD_SEQ 0x40 +#define LFN_END_MARK 0xFFFF +#define LFN_TERM_MARK 0x0000 +#define LFN_FIRST_OFF 0x01 +#define LFN_SIXTH_OFF 0x0E +#define LFN_TWELVETH_OFF 0x1C +#define LFN_FIRST_SET_CNT 5 +#define LFN_SEC_SET_CNT 6 +#define LFN_THIRD_SET_CNT 2 +#define LFN_FIRST_SET_LEN 10 +#define LFN_SEC_SET_LEN 12 +#define LFN_THIRD_SET_LEN 4 +#define LFN_EMPTY_LEN 2 +#define LFN_LEN_PER_ENTRY 13 +#define FNAME_EXTN_SEP_OFF 6 +#define FNAME_SEQ_NUM_OFF 7 +#define BYTES_PER_CLUSTER_ENTRY 4 +#define DIR_ENTRY_LEN 32 +#define VOL_ID_LEN 4 +#define VOL_LABEL_LEN 11 +#define RESERV_LEN 12 +#define FS_VER_LEN 2 +#define OEM_NAME_LEN 8 +#define JUMP_INS_LEN 3 +#define MAX_FAT_CNT 2 +#define SPACE_VAL 32 +#define FILE_READ 0x01 +#define FILE_WRITE 0X02 +#define FILE_CREATE_NEW 0x04 +#define FILE_CREATE_ALWAYS 0x08 +#define FILE_APPEND 0x10 +#define FREE_DIR_ENTRY 0x00 +#define DEL_DIR_ENTRY 0xE5 +#define DOT_DIR_ENTRY 0x2E +#define ASCII_DIFF 32 +#define FILE_SEEK_SET 0 +#define FILE_SEEK_CUR 1 +#define FILE_SEEK_END 2 +#define DELIMITER '/' +#define EXTN_DELIMITER '.' +#define TILDE '~' +#define FULL_SHRT_NAME_LEN 13 + +#pragma pack(push, 1) + +typedef struct +{ + uint8_t status; // 0x80 for bootable, 0x00 for not bootable, anything else for invalid + uint8_t start_head; // The head of the start + uint8_t start_sector; // (S | ((C >> 2) & 0xC0)) where S is the sector of the start and C is the cylinder of the start. Note that S is counted from one. + uint8_t start_cylinder; // (C & 0xFF) where C is the cylinder of the start + uint8_t PartType; + uint8_t end_head; + uint8_t end_sector; + uint8_t end_cylinder; + uint32_t StartLBA; // linear address of first sector in partition. Multiply by sector size (usually 512) for real offset + uint32_t EndLBA; // linear address of last sector in partition. Multiply by sector size (usually 512) for real offset +} mbr_part_t; + +typedef struct +{ + uint8_t Code[440]; + uint32_t DiskSig; //This is optional + uint16_t Reserved; //Usually 0x0000 + mbr_part_t PartTable[4]; + uint8_t BootSignature[2]; //0x55 0xAA for bootable +} mbr_t; + +typedef struct +{ + uint8_t jump[JUMP_INS_LEN]; + uint8_t OEM_name[OEM_NAME_LEN]; + uint16_t bytes_per_sec; + uint8_t sec_per_clus; + uint16_t reserved_sec_cnt; + uint8_t fat_cnt; + uint16_t root_dir_max_cnt; + uint16_t tot_sectors; + uint8_t media_desc; + uint16_t sec_per_fat_fat16; + uint16_t sec_per_track; + uint16_t number_of_heads; + uint32_t hidden_sec_cnt; + uint32_t tol_sector_cnt; + uint32_t sectors_per_fat; + uint16_t ext_flags; + uint8_t fs_version[FS_VER_LEN]; + uint32_t root_dir_strt_cluster; + uint16_t fs_info_sector; + uint16_t backup_boot_sector; + uint8_t reserved[RESERV_LEN]; + uint8_t drive_number; + uint8_t reserved1; + uint8_t boot_sig; + uint8_t volume_id[VOL_ID_LEN]; + uint8_t volume_label[VOL_LABEL_LEN]; + uint8_t file_system_type[FILE_SYS_TYPE_LENGTH]; +} boot_sector; + +typedef struct +{ + uint32_t signature1; /* 0x41615252L */ + uint32_t reserved1[120]; /* Nothing as far as I can tell */ + uint32_t signature2; /* 0x61417272L */ + uint32_t free_clusters; /* Free cluster count. -1 if unknown */ + uint32_t next_cluster; /* Most recently allocated cluster */ + uint32_t reserved2[3]; + uint32_t signature3; +} fsinfo_t; + +typedef struct +{ + uint8_t name[FILE_NAME_SHRT_LEN]; + uint8_t extn[FILE_NAME_EXTN_LEN]; + uint8_t attr; + uint8_t reserved; + uint8_t crt_time_tenth; + uint16_t crt_time; + uint16_t crt_date; + uint16_t lst_access_date; + uint16_t strt_clus_hword; + uint16_t lst_mod_time; + uint16_t lst_mod_date; + uint16_t strt_clus_lword; + uint32_t size; +} dir_entry; + +typedef struct +{ + uint8_t ord_field; + uint8_t fname0_4[LFN_FIRST_SET_LEN]; + uint8_t flag; + uint8_t reserved; + uint8_t chksum; + uint8_t fname6_11[LFN_SEC_SET_LEN]; + uint8_t empty[LFN_EMPTY_LEN]; + uint8_t fname12_13[LFN_THIRD_SET_LEN]; +} lfn_entry; + +#pragma pack(pop) + +bool emfat_init_entries(emfat_entry_t *entries) +{ + emfat_entry_t *e; + int i, n; + + e = &entries[0]; + if (e->level != 0 || !e->dir || e->name == NULL) return false; + + e->priv.top = NULL; + e->priv.next = NULL; + e->priv.sub = NULL; + e->priv.num_subentry = 0; + + n = 0; + for (i = 1; entries[i].name != NULL; i++) { + entries[i].priv.top = NULL; + entries[i].priv.next = NULL; + entries[i].priv.sub = NULL; + entries[i].priv.num_subentry = 0; + if (entries[i].level == n - 1) { + if (n == 0) return false; + e = e->priv.top; + n--; + } + + if (entries[i].level == n + 1) { + if (!e->dir) return false; + e->priv.sub = &entries[i]; + entries[i].priv.top = e; + e = &entries[i]; + n++; + continue; + } + + if (entries[i].level == n) { + if (n == 0) return false; + e->priv.top->priv.num_subentry++; + entries[i].priv.top = e->priv.top; + e->priv.next = &entries[i]; + e = &entries[i]; + continue; + } + + return false; + } + + return true; +} + +static void lba_to_chs(int lba, uint8_t *cl, uint8_t *ch, uint8_t *dh) +{ + int cylinder, head, sector; + int sectors = 63; + int heads = 255; + int cylinders = 1024; + sector = lba % sectors + 1; + head = (lba / sectors) % heads; + cylinder = lba / (sectors * heads); + if (cylinder >= cylinders) { + *cl = *ch = *dh = 0xff; + return; + } + *cl = sector | ((cylinder & 0x300) >> 2); + *ch = cylinder & 0xFF; + *dh = head; +} + +bool emfat_init(emfat_t *emfat, const char *label, emfat_entry_t *entries) +{ + uint32_t sect_per_fat; + uint32_t clust; + uint32_t reserved_clust = 0; + emfat_entry_t *e; + int i; + + if (emfat == NULL || label == NULL || entries == NULL) { + return false; + } + + if (!emfat_init_entries(entries)) { + return false; + } + + clust = 2; + for (i = 0; entries[i].name != NULL; i++) { + e = &entries[i]; + if (e->dir) { + e->curr_size = 0; + e->max_size = 0; + e->priv.first_clust = clust; + e->priv.last_clust = clust + SIZE_TO_NCLUST(e->priv.num_subentry * sizeof(dir_entry)) - 1; + e->priv.last_reserved = e->priv.last_clust; + } else { + e->priv.first_clust = clust; + e->priv.last_clust = e->priv.first_clust + SIZE_TO_NCLUST(entries[i].curr_size) - 1; + e->priv.last_reserved = e->priv.first_clust + SIZE_TO_NCLUST(entries[i].max_size) - 1; + } + reserved_clust += e->priv.last_reserved - e->priv.last_clust; + clust = e->priv.last_reserved + 1; + } + clust -= 2; + + emfat->vol_label = label; + emfat->priv.num_entries = i; + emfat->priv.boot_lba = 62; + emfat->priv.fsinfo_lba = emfat->priv.boot_lba + 1; + emfat->priv.fat1_lba = emfat->priv.fsinfo_lba + 1; + emfat->priv.num_clust = clust; + emfat->priv.free_clust = reserved_clust; + sect_per_fat = SIZE_TO_NSECT((uint64_t)emfat->priv.num_clust * 4); + emfat->priv.fat2_lba = emfat->priv.fat1_lba + sect_per_fat; + emfat->priv.root_lba = emfat->priv.fat2_lba + sect_per_fat; + emfat->priv.entries = entries; + emfat->priv.last_entry = entries; + emfat->disk_sectors = clust * SECT_PER_CLUST + emfat->priv.root_lba; + emfat->vol_size = (uint64_t)emfat->disk_sectors * SECT; + /* calc cyl number */ +// i = ((emfat->disk_sectors + 63*255 - 1) / (63*255)); +// emfat->disk_sectors = i * 63*255; + return true; +} + +void read_mbr_sector(const emfat_t *emfat, uint8_t *sect) +{ + mbr_t *mbr; + memset(sect, 0, SECT); + mbr = (mbr_t *)sect; + mbr->DiskSig = 0; + mbr->Reserved = 0; + mbr->PartTable[0].status = 0x80; + mbr->PartTable[0].PartType = 0x0C; + mbr->PartTable[0].StartLBA = emfat->priv.boot_lba; + mbr->PartTable[0].EndLBA = emfat->disk_sectors; + lba_to_chs(mbr->PartTable[0].StartLBA, &mbr->PartTable[0].start_sector, &mbr->PartTable[0].start_cylinder, &mbr->PartTable[0].start_head); + lba_to_chs(emfat->disk_sectors - 1, &mbr->PartTable[0].end_sector, &mbr->PartTable[0].end_cylinder, &mbr->PartTable[0].end_head); + mbr->BootSignature[0] = 0x55; + mbr->BootSignature[1] = 0xAA; +} + +void read_boot_sector(const emfat_t *emfat, uint8_t *sect) +{ + boot_sector *bs; + memset(sect, 0, SECT); + bs = (boot_sector *)sect; + bs->jump[0] = 0xEB; + bs->jump[1] = 0x58; + bs->jump[2] = 0x90; + memcpy(bs->OEM_name, "MSDOS5.0", 8); + bs->bytes_per_sec = SECT; + bs->sec_per_clus = 8; /* 4 kb per cluster */ + bs->reserved_sec_cnt = 2; /* boot sector & fsinfo sector */ + bs->fat_cnt = 2; /* two tables */ + bs->root_dir_max_cnt = 0; + bs->tot_sectors = 0; + bs->media_desc = 0xF8; + bs->sec_per_fat_fat16 = 0; + bs->sec_per_track = 63; + bs->number_of_heads = 0xFF; + bs->hidden_sec_cnt = 62; + bs->tol_sector_cnt = emfat->disk_sectors - emfat->priv.boot_lba; + bs->sectors_per_fat = emfat->priv.fat2_lba - emfat->priv.fat1_lba; + bs->ext_flags = 0; + bs->fs_version[0] = 0; + bs->fs_version[1] = 0; + bs->root_dir_strt_cluster = 2; + bs->fs_info_sector = 1; + bs->backup_boot_sector = 0; /* not used */ + bs->drive_number = 128; + bs->boot_sig = 0x29; + bs->volume_id[0] = 148; + bs->volume_id[1] = 14; + bs->volume_id[2] = 13; + bs->volume_id[3] = 8; + memcpy(bs->volume_label, "NO NAME ", 12); + memcpy(bs->file_system_type, "FAT32 ", 8); + sect[SECT - 2] = 0x55; + sect[SECT - 1] = 0xAA; +} + +#define IS_CLUST_OF(clust, entry) ((clust) >= (entry)->priv.first_clust && (clust) <= (entry)->priv.last_reserved) + +emfat_entry_t *find_entry(const emfat_t *emfat, uint32_t clust, emfat_entry_t *nearest) +{ + if (nearest == NULL) { + nearest = emfat->priv.entries; + } + + if (nearest->priv.first_clust > clust) { + while (nearest >= emfat->priv.entries) { // backward finding + if (IS_CLUST_OF(clust, nearest)) + return nearest; + nearest--; + } + } else { + while (nearest->name != NULL) { // forward finding + if (IS_CLUST_OF(clust, nearest)) + return nearest; + nearest++; + } + } + return NULL; +} + +void read_fsinfo_sector(const emfat_t *emfat, uint8_t *sect) +{ + UNUSED(emfat); + + fsinfo_t *info = (fsinfo_t *)sect; + info->signature1 = 0x41615252L; + info->signature2 = 0x61417272L; + //info->free_clusters = 0; + info->free_clusters = emfat->priv.free_clust; + //info->next_cluster = emfat->priv.num_clust + 2; + info->next_cluster = 0xffffffff; + memset(info->reserved1, 0, sizeof(info->reserved1)); + memset(info->reserved2, 0, sizeof(info->reserved2)); + info->signature3 = 0xAA550000; +} + +void read_fat_sector(emfat_t *emfat, uint8_t *sect, uint32_t index) +{ + emfat_entry_t *le; + uint32_t *values; + uint32_t count; + uint32_t curr; + + values = (uint32_t *)sect; + curr = index * 128; + count = 128; + + if (curr == 0) { + *values++ = CLUST_ROOT_END; + *values++ = 0xFFFFFFFF; + count -= 2; + curr += 2; + } + + le = emfat->priv.last_entry; + while (count != 0) { + if (!IS_CLUST_OF(curr, le)) { + le = find_entry(emfat, curr, le); + if (le == NULL) { + le = emfat->priv.last_entry; + *values = CLUST_RESERVED; + values++; + count--; + curr++; + continue; + } + } + if (le->dir) { + if (curr == le->priv.last_clust) { + *values = CLUST_EOF; + } else { + *values = curr + 1; + } + } else { + if (curr == le->priv.last_clust) { + *values = CLUST_EOF; + } else if (curr > le->priv.last_clust) { + *values = CLUST_FREE; + } else { + *values = curr + 1; + } + } + values++; + count--; + curr++; + } + emfat->priv.last_entry = le; +} + +void fill_entry(dir_entry *entry, const char *name, uint8_t attr, uint32_t clust, const uint32_t cma[3], uint32_t size) +{ + int i, l, l1, l2; + int dot_pos; + + memset(entry, 0, sizeof(dir_entry)); + + if (cma) { + entry->crt_date = cma[0] >> 16; + entry->crt_time = cma[0] & 0xFFFF; + entry->lst_mod_date = cma[1] >> 16; + entry->lst_mod_time = cma[1] & 0xFFFF; + entry->lst_access_date = cma[2] >> 16; + } + + l = strlen(name); + dot_pos = -1; + + if ((attr & ATTR_DIR) == 0) { + for (i = l - 1; i >= 0; i--) { + if (name[i] == '.') + { + dot_pos = i; + break; + } + } + } + + if (dot_pos == -1) { + l1 = l > FILE_NAME_SHRT_LEN ? FILE_NAME_SHRT_LEN : l; + l2 = 0; + } else { + l1 = dot_pos; + l1 = l1 > FILE_NAME_SHRT_LEN ? FILE_NAME_SHRT_LEN : l1; + l2 = l - dot_pos - 1; + l2 = l2 > FILE_NAME_EXTN_LEN ? FILE_NAME_EXTN_LEN : l2; + } + + memset(entry->name, ' ', FILE_NAME_SHRT_LEN + FILE_NAME_EXTN_LEN); + memcpy(entry->name, name, l1); + memcpy(entry->extn, name + dot_pos + 1, l2); + + for (i = 0; i < FILE_NAME_SHRT_LEN; i++) { + if (entry->name[i] >= 'a' && entry->name[i] <= 'z') { + entry->name[i] -= 0x20; + } + } + + for (i = 0; i < FILE_NAME_EXTN_LEN; i++) { + if (entry->extn[i] >= 'a' && entry->extn[i] <= 'z') { + entry->extn[i] -= 0x20; + } + } + + entry->attr = attr; + entry->reserved = 24; + entry->strt_clus_hword = clust >> 16; + entry->strt_clus_lword = clust; + entry->size = size; + + return; +} + +void fill_dir_sector(emfat_t *emfat, uint8_t *data, emfat_entry_t *entry, uint32_t rel_sect) +{ + dir_entry *de; + uint32_t avail; + + memset(data, 0, SECT); + de = (dir_entry *)data; + avail = SECT; + + if (rel_sect == 0) { // 1. first sector of directory + if (entry->priv.top == NULL) { + fill_entry(de++, emfat->vol_label, ATTR_VOL_LABEL, 0, 0, 0); + avail -= sizeof(dir_entry); + } else { + fill_entry(de++, ".", ATTR_DIR | ATTR_READ, entry->priv.first_clust, 0, 0); + if (entry->priv.top->priv.top == NULL) { + fill_entry(de++, "..", ATTR_DIR | ATTR_READ, 0, 0, 0); + } else { + fill_entry(de++, "..", ATTR_DIR | ATTR_READ, entry->priv.top->priv.first_clust, 0, 0); + } + avail -= sizeof(dir_entry) * 2; + } + entry = entry->priv.sub; + } else { // 2. not a first sector + int n; + n = rel_sect * (SECT / sizeof(dir_entry)); + n -= entry->priv.top == NULL ? 1 : 2; + entry = entry->priv.sub; + + while (n > 0 && entry != NULL) { + entry = entry->priv.next; + n--; + } + } + + while (entry != NULL && avail >= sizeof(dir_entry)) { + if (entry->dir) { + fill_entry(de++, entry->name, ATTR_DIR | ATTR_READ, entry->priv.first_clust, entry->cma_time, 0); + } else { + //fill_entry(de++, entry->name, ATTR_ARCHIVE | ATTR_READ, entry->priv.first_clust, entry->cma_time, entry->curr_size); + fill_entry(de++, entry->name, ATTR_ARCHIVE | ATTR_READ | entry->attr, entry->priv.first_clust, entry->cma_time, entry->curr_size); + } + entry = entry->priv.next; + avail -= sizeof(dir_entry); + } +} + +void read_data_sector(emfat_t *emfat, uint8_t *data, uint32_t rel_sect) +{ + emfat_entry_t *le; + uint32_t cluster; + cluster = rel_sect / 8 + 2; + rel_sect = rel_sect % 8; + + le = emfat->priv.last_entry; + if (!IS_CLUST_OF(cluster, le)) { + le = find_entry(emfat, cluster, le); + if (le == NULL) { + int i; + for (i = 0; i < SECT / 4; i++) + ((uint32_t *)data)[i] = 0xEFBEADDE; + return; + } + emfat->priv.last_entry = le; + } + + if (le->dir) { + fill_dir_sector(emfat, data, le, rel_sect); + return; + } + + if (le->readcb == NULL) { + memset(data, 0, SECT); + } else { + uint32_t offset = cluster - le->priv.first_clust; + offset = offset * CLUST + rel_sect * SECT; + le->readcb(data, SECT, offset + le->offset, le); + } + + return; +} + +void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors) +{ + while (num_sectors > 0) { + if (sector >= emfat->priv.root_lba) { + read_data_sector(emfat, data, sector - emfat->priv.root_lba); + } else if (sector == 0) { + read_mbr_sector(emfat, data); + } else if (sector == emfat->priv.fsinfo_lba) { + read_fsinfo_sector(emfat, data); + } else if (sector == emfat->priv.boot_lba) { + read_boot_sector(emfat, data); + } else if (sector >= emfat->priv.fat1_lba && sector < emfat->priv.fat2_lba) { + read_fat_sector(emfat, data, sector - emfat->priv.fat1_lba); + } else if (sector >= emfat->priv.fat2_lba && sector < emfat->priv.root_lba) { + read_fat_sector(emfat, data, sector - emfat->priv.fat2_lba); + } else { + memset(data, 0, SECT); + } + data += SECT; + num_sectors--; + sector++; + } +} + +void write_data_sector(emfat_t *emfat, const uint8_t *data, uint32_t rel_sect) +{ + emfat_entry_t *le; + uint32_t cluster; + cluster = rel_sect / 8 + 2; + rel_sect = rel_sect % 8; + + le = emfat->priv.last_entry; + + if (!IS_CLUST_OF(cluster, le)) { + le = find_entry(emfat, cluster, le); + if (le == NULL) return; + emfat->priv.last_entry = le; + } + + if (le->dir) { + // TODO: handle changing a filesize + return; + } + + if (le->writecb != NULL) { + le->writecb(data, SECT, rel_sect * SECT + le->offset, le); + } +} + +#define FEBRUARY 2 +#define STARTOFTIME 1970 +#define SECDAY 86400L +#define SECYR (SECDAY * 365) +#define leapyear(year) ((year) % 4 == 0) +#define days_in_year(a) (leapyear(a) ? 366 : 365) +#define days_in_month(a) (month_days[(a) - 1]) + +static int month_days[12] = { + 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 +}; + +uint32_t emfat_cma_time_from_unix(uint32_t tim) +{ + register int i; + register long tmp, day; + int ymd[3]; + int hms[3]; + + day = tim / SECDAY; + tmp = tim % SECDAY; + + /* Hours, minutes, seconds are easy */ + + hms[0] = tmp / 3600; + hms[1] = (tmp % 3600) / 60; + hms[2] = (tmp % 3600) % 60; + + /* Number of years in days */ + for (i = STARTOFTIME; day >= days_in_year(i); i++) + day -= days_in_year(i); + ymd[0] = i; + + /* Number of months in days left */ + if (leapyear(ymd[0])) { + days_in_month(FEBRUARY) = 29; + } + for (i = 1; day >= days_in_month(i); i++) { + day -= days_in_month(i); + } + days_in_month(FEBRUARY) = 28; + ymd[1] = i; + + /* Days are what is left over (+1) from all that. */ + ymd[2] = day + 1; + + return EMFAT_ENCODE_CMA_TIME(ymd[2], ymd[1], ymd[0], hms[0], hms[1], hms[2]); +} + +#ifdef __cplusplus +} +#endif diff --git a/src/main/msc/emfat.h b/src/main/msc/emfat.h new file mode 100644 index 00000000000..ada82fb8cf2 --- /dev/null +++ b/src/main/msc/emfat.h @@ -0,0 +1,113 @@ +/* + * Derived from + * https://github.com/fetisov/emfat/blob/master/project/emfat.c + * version: 1.0 (4.01.2015) + */ + +/* + * The MIT License (MIT) + * + * Copyright (c) 2015 by Sergey Fetisov + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#pragma once + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +struct emfat_entry_s; +typedef void (*emfat_readcb_t)(uint8_t *dest, int size, uint32_t offset, struct emfat_entry_s *entry); +typedef void (*emfat_writecb_t)(const uint8_t *data, int size, uint32_t offset, struct emfat_entry_s *entry); + +typedef struct emfat_entry_s { + const char *name; + bool dir; + uint8_t attr; + int level; + uint32_t offset; + uint32_t curr_size; + uint32_t max_size; + long user_data; + uint32_t cma_time[3]; /**< create/mod/access time in unix format */ + emfat_readcb_t readcb; + emfat_writecb_t writecb; + struct + { + uint32_t first_clust; + uint32_t last_clust; + uint32_t last_reserved; + uint32_t num_subentry; + struct emfat_entry_s *top; + struct emfat_entry_s *sub; + struct emfat_entry_s *next; + } priv; +} emfat_entry_t; + +typedef struct emfat_s { + uint64_t vol_size; + uint32_t disk_sectors; + const char *vol_label; + struct { + uint32_t boot_lba; + uint32_t fsinfo_lba; + uint32_t fat1_lba; + uint32_t fat2_lba; + uint32_t root_lba; + uint32_t num_clust; + uint32_t free_clust; + emfat_entry_t *entries; + emfat_entry_t *last_entry; + int num_entries; + } priv; +} emfat_t; + +bool emfat_init(emfat_t *emfat, const char *label, emfat_entry_t *entries); +void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors); +void emfat_write(emfat_t *emfat, const uint8_t *data, uint32_t sector, int num_sectors); + +#define EMFAT_ENCODE_CMA_TIME(D,M,Y,h,m,s) \ + ((((((Y)-1980) << 9) | ((M) << 5) | (D)) << 16) | \ + (((h) << 11) | ((m) << 5) | (s >> 1))) + +static inline uint32_t emfat_encode_cma_time(int D, int M, int Y, int h, int m, int s) +{ + return EMFAT_ENCODE_CMA_TIME(D,M,Y,h,m,s); +} + +uint32_t emfat_cma_time_from_unix(uint32_t unix_time); + +#define ATTR_READ 0x01 +#define ATTR_HIDDEN 0x02 +#define ATTR_SYSTEM 0x04 +#define ATTR_VOL_LABEL 0x08 +#define ATTR_DIR 0x10 +#define ATTR_ARCHIVE 0x20 +#define ATTR_LONG_FNAME 0x0F + +#ifdef __cplusplus +} +#endif diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c new file mode 100644 index 00000000000..d95a9e75a7d --- /dev/null +++ b/src/main/msc/emfat_file.c @@ -0,0 +1,334 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: jflyper@github.com + */ + +#include "common/utils.h" +#include "common/printf.h" + +#include "emfat.h" +#include "emfat_file.h" + +#include "io/flashfs.h" + +#define USE_EMFAT_AUTORUN +#define USE_EMFAT_ICON +//#define USE_EMFAT_README + +#ifdef USE_EMFAT_AUTORUN +static const char autorun_file[] = + "[autorun]\r\n" + "icon=icon.ico\r\n" + "label=Betaflight Onboard Flash\r\n" ; +#define AUTORUN_SIZE (sizeof(autorun_file) - 1) +#define EMFAT_INCR_AUTORUN 1 +#else +#define EMFAT_INCR_AUTORUN 0 +#endif + +#ifdef USE_EMFAT_README +static const char readme_file[] = + "This is readme file\r\n"; +#define README_SIZE (sizeof(readme_file) - 1) +#define EMFAT_INCR_README 1 +#else +#define EMFAT_INCR_README 0 +#endif + +#ifdef USE_EMFAT_ICON +static const char icon_file[] = +{ + 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x28, 0x09, + 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0xfc, + 0xfc, 0xde, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, + 0xfb, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfc, 0xfc, + 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xde, 0xfb, 0xfb, + 0xfb, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xf4, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, + 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, + 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xfb, + 0xfc, 0xff, 0xd7, 0xdd, 0xe1, 0xff, 0xc7, 0xc3, 0xc2, 0xff, 0xce, 0xce, 0xce, 0xff, 0xe2, 0xe4, + 0xe5, 0xff, 0xfd, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, + 0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb0, 0xad, 0xad, 0xff, 0x3a, 0x89, + 0xa8, 0xff, 0x03, 0xb5, 0xed, 0xff, 0x20, 0x57, 0x6c, 0xff, 0x36, 0x25, 0x1f, 0xff, 0x34, 0x52, + 0x5e, 0xff, 0x4f, 0x65, 0x6e, 0xff, 0x8a, 0x86, 0x84, 0xff, 0xd8, 0xd8, 0xd8, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfa, 0xfa, + 0xfa, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, + 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb2, 0xb1, 0xff, 0x2a, 0x1d, 0x18, 0xff, 0x33, 0x2a, + 0x26, 0xff, 0x25, 0x68, 0x7f, 0xff, 0x16, 0x90, 0xbe, 0xff, 0x3a, 0x38, 0x37, 0xff, 0x37, 0x38, + 0x38, 0xff, 0x31, 0x35, 0x37, 0xff, 0x29, 0x28, 0x27, 0xff, 0x34, 0x34, 0x34, 0xff, 0x93, 0x93, + 0x93, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xfc, 0xf8, 0xff, 0x4f, 0xa0, 0xbf, 0xff, 0x0d, 0x8c, 0xb8, 0xff, 0x2c, 0x62, + 0x76, 0xff, 0x3e, 0x31, 0x2e, 0xff, 0x36, 0x46, 0x4d, 0xff, 0x38, 0x41, 0x44, 0xff, 0x3b, 0x39, + 0x38, 0xff, 0x37, 0x36, 0x35, 0xff, 0x2c, 0x2c, 0x2c, 0xff, 0x28, 0x28, 0x28, 0xff, 0x83, 0x83, + 0x83, 0xff, 0x77, 0x77, 0x77, 0xff, 0xd5, 0xd5, 0xd5, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, + 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xfd, 0xfb, 0xff, 0x5f, 0x98, 0xad, 0xff, 0x1a, 0x5c, 0x73, 0xff, 0x30, 0x5a, + 0x6a, 0xff, 0x38, 0x42, 0x46, 0xff, 0x3c, 0x35, 0x33, 0xff, 0x39, 0x38, 0x37, 0xff, 0x2b, 0x2b, + 0x2b, 0xff, 0x3c, 0x3c, 0x3c, 0xff, 0x83, 0x83, 0x83, 0xff, 0xc2, 0xc2, 0xc2, 0xff, 0xd2, 0xd2, + 0xd2, 0xff, 0xa9, 0xa9, 0xa9, 0xff, 0x86, 0x86, 0x86, 0xff, 0xdf, 0xdf, 0xdf, 0xee, 0xfc, 0xfc, + 0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc3, 0xba, 0xb7, 0xff, 0x2c, 0x21, 0x1d, 0xff, 0x38, 0x30, + 0x2d, 0xff, 0x3c, 0x3a, 0x39, 0xff, 0x34, 0x35, 0x35, 0xff, 0x2e, 0x2e, 0x2e, 0xff, 0x78, 0x78, + 0x78, 0xff, 0xdf, 0xdf, 0xdf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xeb, 0xeb, 0xeb, 0xee, 0xfa, 0xfa, + 0xfa, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, + 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb3, 0xb0, 0xaf, 0xff, 0x3d, 0x31, + 0x2c, 0xff, 0x33, 0x30, 0x2f, 0xff, 0x49, 0x4a, 0x4a, 0xff, 0xcb, 0xcb, 0xcb, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, + 0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd3, 0xe2, 0xe8, 0xff, 0x1c, 0x85, + 0xae, 0xff, 0x2f, 0x44, 0x4c, 0xff, 0x41, 0x3c, 0x3a, 0xff, 0x9a, 0x9a, 0x9a, 0xff, 0xf9, 0xf9, + 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xf5, 0xf5, + 0xf5, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0x8a, 0xd0, 0xea, 0xff, 0x00, 0xb0, + 0xf7, 0xff, 0x36, 0x49, 0x51, 0xff, 0x39, 0x33, 0x31, 0xff, 0x1f, 0x1f, 0x1f, 0xff, 0x98, 0x98, + 0x98, 0xff, 0xe2, 0xe2, 0xe2, 0xff, 0x9b, 0x9b, 0x9b, 0xff, 0x71, 0x71, 0x71, 0xff, 0x72, 0x72, + 0x72, 0xff, 0x63, 0x63, 0x63, 0xff, 0xef, 0xef, 0xef, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xf4, + 0xf4, 0xff, 0xae, 0xae, 0xae, 0xff, 0x8c, 0x8c, 0x8c, 0xff, 0x86, 0x86, 0x86, 0xff, 0x84, 0x84, + 0x84, 0xff, 0x86, 0x86, 0x86, 0xff, 0x91, 0x8a, 0x87, 0xff, 0x48, 0x7a, 0x8d, 0xff, 0x00, 0x9c, + 0xd7, 0xff, 0x3a, 0x3e, 0x3f, 0xff, 0x39, 0x36, 0x35, 0xff, 0x35, 0x35, 0x35, 0xff, 0x42, 0x42, + 0x42, 0xff, 0x3b, 0x3b, 0x3b, 0xff, 0x31, 0x31, 0x31, 0xff, 0x92, 0x92, 0x92, 0xff, 0x90, 0x90, + 0x90, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, + 0xfb, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xde, 0xde, 0xde, 0xff, 0x80, 0x80, + 0x80, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xe6, 0xe6, 0xe6, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xea, 0xea, 0xea, 0xff, 0x81, 0x80, 0x80, 0xff, 0x49, 0x42, 0x40, 0xff, 0x55, 0x8e, + 0xa3, 0xff, 0x1f, 0x5b, 0x72, 0xff, 0x35, 0x3a, 0x3c, 0xff, 0x43, 0x41, 0x41, 0xff, 0x35, 0x35, + 0x35, 0xff, 0x2a, 0x2a, 0x2a, 0xff, 0xbe, 0xbe, 0xbe, 0xff, 0xe8, 0xe8, 0xe8, 0xff, 0x6f, 0x6f, + 0x6f, 0xff, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, + 0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xf5, 0xf5, 0xf5, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xe0, 0xe0, + 0xe0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xb8, 0xb8, + 0xb8, 0xff, 0x7d, 0x7d, 0x7d, 0xff, 0xa3, 0xa3, 0xa3, 0xff, 0xd2, 0xd2, 0xd2, 0xff, 0x87, 0x7c, + 0x77, 0xff, 0x5a, 0x57, 0x55, 0xff, 0xca, 0xcb, 0xcb, 0xff, 0x82, 0x82, 0x82, 0xff, 0x23, 0x23, + 0x23, 0xff, 0x38, 0x38, 0x38, 0xff, 0x43, 0x43, 0x43, 0xff, 0x5d, 0x5d, 0x5d, 0xff, 0xd9, 0xd9, + 0xd9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xa1, 0xa1, 0xa1, 0xff, 0xb6, 0xb6, 0xb6, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xc7, 0xc7, + 0xc7, 0xff, 0xea, 0xea, 0xea, 0xff, 0xa6, 0xa6, 0xa6, 0xff, 0x60, 0x60, 0x60, 0xff, 0x9f, 0x9f, + 0x9f, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd1, 0xd1, 0xd1, 0xff, 0x4e, 0x4e, + 0x4e, 0xff, 0x29, 0x29, 0x29, 0xff, 0x73, 0x73, 0x73, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xec, 0xec, 0xec, 0xff, 0x90, 0x90, 0x90, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xf0, 0xf0, 0xf0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb7, + 0xb7, 0xff, 0x61, 0x61, 0x61, 0xff, 0x89, 0x89, 0x89, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xdc, 0xdc, 0xdc, 0xff, 0x99, 0x99, + 0x99, 0xff, 0xbc, 0xbc, 0xbc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0x98, 0x98, 0x98, 0xff, 0x9c, 0x9c, 0x9c, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc5, 0xc5, 0xc5, 0xff, 0x66, 0x66, 0x66, 0xff, 0x76, 0x76, + 0x76, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdd, 0xdd, 0xdd, 0xff, 0xcd, 0xcd, 0xcd, 0xff, 0xf7, 0xf7, + 0xf7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xda, 0xda, + 0xda, 0xee, 0x48, 0x48, 0x48, 0xff, 0x75, 0x75, 0x75, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd5, 0xd5, + 0xd5, 0xff, 0x72, 0x72, 0x72, 0xff, 0x6a, 0x6a, 0x6a, 0xff, 0xc8, 0xc8, 0xc8, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xeb, 0xeb, + 0xeb, 0xee, 0xaf, 0xaf, 0xaf, 0xff, 0xb0, 0xb0, 0xb0, 0xff, 0x8b, 0x8b, 0x8b, 0xff, 0x60, 0x60, + 0x60, 0xff, 0xb3, 0xb3, 0xb3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, + 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0x66, 0x66, 0x66, 0xff, 0x54, 0x54, 0x54, 0xff, 0xa0, 0xa0, 0xa0, 0xff, 0xfa, 0xfa, + 0xfa, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, + 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, + 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xce, 0xce, + 0xce, 0xee, 0x98, 0x98, 0x98, 0xff, 0xef, 0xef, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xf6, 0xf6, + 0xf6, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xf4, 0xfd, 0xfd, + 0xfd, 0xde, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, + 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xde, +}; + +#define ICON_SIZE (sizeof(icon_file)) +#define EMFAT_INCR_ICON 1 +#else +#define EMFAT_INCR_ICON 0 +#endif + +#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1,1,2018, 13,0,0) +#define CMA { CMA_TIME, CMA_TIME, CMA_TIME } + +static void memory_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry) +{ + int len; + + if (offset > entry->curr_size) { + return; + } + + if (offset + size > entry->curr_size) { + len = entry->curr_size - offset; + } else { + len = size; + } + + memcpy(dest, &((char *)entry->user_data)[offset], len); +} + +static void bblog_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry) +{ + UNUSED(entry); + + flashfsReadAbs(offset, dest, size); +} + +static const emfat_entry_t entriesPredefined[] = +{ + // name dir attr lvl offset size max_size user time read write + { "", true, 0, 0, 0, 0, 0, 0, CMA, NULL, NULL, { 0 } }, +#ifdef USE_EMFAT_AUTORUN + { "autorun.inf", false, ATTR_HIDDEN, 1, 0, AUTORUN_SIZE, AUTORUN_SIZE, (long)autorun_file, CMA, memory_read_proc, NULL, { 0 } }, +#endif +#ifdef USE_EMFAT_ICON + { "icon.ico", false, ATTR_HIDDEN, 1, 0, ICON_SIZE, ICON_SIZE, (long)icon_file, CMA, memory_read_proc, NULL, { 0 } }, +#endif +#ifdef USE_EMFAT_README + { "readme.txt", false, 0, 1, 0, README_SIZE, 1024*1024, (long)readme_file, CMA, memory_read_proc, NULL, { 0 } }, +#endif + { "BTFL_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } }, +}; + +#define ENTRY_INDEX_BBL (1 + EMFAT_INCR_AUTORUN + EMFAT_INCR_ICON + EMFAT_INCR_README) + +#define EMFAT_MAX_LOG_ENTRY 100 +#define EMFAT_MAX_ENTRY (ENTRY_INDEX_BBL + EMFAT_MAX_LOG_ENTRY) + +static emfat_entry_t entries[EMFAT_MAX_ENTRY]; +static char logNames[EMFAT_MAX_LOG_ENTRY][8+3]; + +emfat_t emfat; + +static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uint32_t size) +{ + tfp_sprintf(logNames[number], "BTFL_%03d.BBL", number); + entry->name = logNames[number]; + entry->level = 1; + entry->offset = offset; + entry->curr_size = size; + entry->max_size = entry->curr_size; + entry->cma_time[0] = CMA_TIME; + entry->cma_time[1] = CMA_TIME; + entry->cma_time[2] = CMA_TIME; + entry->readcb = bblog_read_proc; +} + +static void emfat_find_log(emfat_entry_t *entry, int maxCount) +{ + uint32_t limit = flashfsIdentifyStartOfFreeSpace(); + uint32_t lastOffset = 0; + uint32_t currOffset = 0; + int fileNumber = 0; + uint8_t buffer[18]; + + for ( ; currOffset < limit ; currOffset += 2048) { // XXX 2048 = FREE_BLOCK_SIZE in io/flashfs.c + + flashfsReadAbs(currOffset, buffer, 18); + + if (strncmp((char *)buffer, "H Product:Blackbox", 18)) { + continue; + } + + if (lastOffset != currOffset) { + emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset); + + ++fileNumber; + if (fileNumber == maxCount) { + break; + } + ++entry; + } + + lastOffset = currOffset; + } + + if (fileNumber != maxCount && lastOffset != currOffset) { + emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset); + } +} + +void emfat_init_files(void) +{ + memset(entries, 0, sizeof(entries)); + + for (size_t i = 0 ; i < ARRAYLEN(entriesPredefined) ; i++) { + entries[i] = entriesPredefined[i]; + } + + // Singleton + emfat_entry_t *entry = &entries[ENTRY_INDEX_BBL]; + entry->curr_size = flashfsIdentifyStartOfFreeSpace(); + entry->max_size = flashfsGetSize(); + + // Detect and list individual power cycle sessions + emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1)); + + emfat_init(&emfat, "emfat", entries); +} diff --git a/src/main/msc/emfat_file.h b/src/main/msc/emfat_file.h new file mode 100644 index 00000000000..139e181fe38 --- /dev/null +++ b/src/main/msc/emfat_file.h @@ -0,0 +1,23 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +void emfat_init_files(void); diff --git a/src/main/msc/usbd_msc_desc.c b/src/main/msc/usbd_msc_desc.c new file mode 100644 index 00000000000..a72c8b83c43 --- /dev/null +++ b/src/main/msc/usbd_msc_desc.c @@ -0,0 +1,383 @@ +/** + ****************************************************************************** + * @file usbd_desc.c + * @author MCD Application Team + * @version V1.2.0 + * @date 09-November-2015 + * @brief This file provides the USBD descriptors and string formating method. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * 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. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_core.h" +#include "usbd_desc.h" +#include "usbd_req.h" +#include "usbd_conf.h" +#include "usb_regs.h" +#include "platform.h" + +#define DEVICE_ID1 (0x1FFFF7E8) +#define DEVICE_ID2 (0x1FFFF7EA) +#define DEVICE_ID3 (0x1FFFF7EC) +#define USB_SIZ_STRING_SERIAL 0x1A + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + + +/** @defgroup USBD_DESC + * @brief USBD descriptors module + * @{ + */ + +/** @defgroup USBD_DESC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_DESC_Private_Defines + * @{ + */ + +#define USBD_VID 0x0483 +#define USBD_PID 0x5720 + +#define USBD_LANGID_STRING 0x409 +#define USBD_MANUFACTURER_STRING "STMicroelectronics" +#define USBD_PRODUCT_HS_STRING "Mass Storage in HS Mode" +#define USBD_PRODUCT_FS_STRING "Mass Storage in FS Mode" +#define USBD_CONFIGURATION_HS_STRING "MSC Config" +#define USBD_INTERFACE_HS_STRING "MSC Interface" +#define USBD_CONFIGURATION_FS_STRING "MSC Config" +#define USBD_INTERFACE_FS_STRING "MSC Interface" +/** + * @} + */ + + +/** @defgroup USBD_DESC_Private_Macros + * @{ + */ +/** + * @} + */ + + +/** @defgroup USBD_DESC_Private_Variables + * @{ + */ + +USBD_DEVICE MSC_desc = +{ + USBD_MSC_DeviceDescriptor, + USBD_MSC_LangIDStrDescriptor, + USBD_MSC_ManufacturerStrDescriptor, + USBD_MSC_ProductStrDescriptor, + USBD_MSC_SerialStrDescriptor, + USBD_MSC_ConfigStrDescriptor, + USBD_MSC_InterfaceStrDescriptor, +}; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +/* USB Standard Device Descriptor */ +__ALIGN_BEGIN uint8_t USBD_DeviceDesc_MSC[USB_SIZ_DEVICE_DESC] __ALIGN_END = +{ + 0x12, /*bLength */ + USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/ + 0x00, /*bcdUSB */ + 0x02, + 0x00, /*bDeviceClass*/ + 0x00, /*bDeviceSubClass*/ + 0x00, /*bDeviceProtocol*/ + USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/ + LOBYTE(USBD_VID), /*idVendor*/ + HIBYTE(USBD_VID), /*idVendor*/ + LOBYTE(USBD_PID), /*idVendor*/ + HIBYTE(USBD_PID), /*idVendor*/ + 0x00, /*bcdDevice rel. 2.00*/ + 0x02, + USBD_IDX_MFC_STR, /*Index of manufacturer string*/ + USBD_IDX_PRODUCT_STR, /*Index of product string*/ + USBD_IDX_SERIAL_STR, /*Index of serial number string*/ + USBD_CFG_MAX_NUM /*bNumConfigurations*/ +} ; /* USB_DeviceDescriptor */ + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +/* USB Standard Device Descriptor */ +__ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc_MSC[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END = +{ + USB_LEN_DEV_QUALIFIER_DESC, + USB_DESC_TYPE_DEVICE_QUALIFIER, + 0x00, + 0x02, + 0x00, + 0x00, + 0x00, + 0x40, + 0x01, + 0x00, +}; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +/* USB Standard Device Descriptor */ +__ALIGN_BEGIN uint8_t USBD_LangIDDesc_MSC[USB_SIZ_STRING_LANGID] __ALIGN_END = +{ + USB_SIZ_STRING_LANGID, + USB_DESC_TYPE_STRING, + LOBYTE(USBD_LANGID_STRING), + HIBYTE(USBD_LANGID_STRING), +}; + +uint8_t USBD_StringSerial_MSC[USB_SIZ_STRING_SERIAL] = +{ + USB_SIZ_STRING_SERIAL, + USB_DESC_TYPE_STRING, +}; + +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED + #if defined ( __ICCARM__ ) /*!< IAR Compiler */ + #pragma data_alignment=4 + #endif +#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ +__ALIGN_BEGIN uint8_t USBD_StrDesc_MSC[USB_MAX_STR_DESC_SIZ] __ALIGN_END ; + +/** + * @} + */ + + +/** @defgroup USBD_DESC_Private_FunctionPrototypes + * @{ + */ +static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void Get_SerialNum(void); +/** + * @} + */ + + +/** @defgroup USBD_DESC_Private_Functions + * @{ + */ + +/** +* @brief USBD_USR_DeviceDescriptor +* return the device descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_DeviceDescriptor( uint8_t speed , uint16_t *length) +{ + (void)(speed); + *length = sizeof(USBD_DeviceDesc_MSC); + return (uint8_t*)USBD_DeviceDesc_MSC; +} + +/** +* @brief USBD_USR_LangIDStrDescriptor +* return the LangID string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_LangIDStrDescriptor( uint8_t speed , uint16_t *length) +{ + (void)(speed); + *length = sizeof(USBD_LangIDDesc_MSC); + return (uint8_t*)USBD_LangIDDesc_MSC; +} + + +/** +* @brief USBD_USR_ProductStrDescriptor +* return the product string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_ProductStrDescriptor( uint8_t speed , uint16_t *length) +{ + if(speed == 0) + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc_MSC, length); + } + else + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc_MSC, length); + } + return USBD_StrDesc_MSC; +} + +/** +* @brief USBD_USR_ManufacturerStrDescriptor +* return the manufacturer string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length) +{ + (void)(speed); + USBD_GetString((uint8_t *)(uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc_MSC, length); + return USBD_StrDesc_MSC; +} + +/** +* @brief USBD_USR_SerialStrDescriptor +* return the serial number string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_SerialStrDescriptor( uint8_t speed , uint16_t *length) +{ + (void)(speed); + *length = USB_SIZ_STRING_SERIAL; + + /* Update the serial number string descriptor with the data from the unique ID*/ + Get_SerialNum(); + + return (uint8_t*)USBD_StringSerial_MSC; +} + +/** +* @brief USBD_USR_ConfigStrDescriptor +* return the configuration string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_ConfigStrDescriptor( uint8_t speed , uint16_t *length) +{ + if(speed == USB_OTG_SPEED_HIGH) + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc_MSC, length); + } + else + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc_MSC, length); + } + return USBD_StrDesc_MSC; +} + + +/** +* @brief USBD_USR_InterfaceStrDescriptor +* return the interface string descriptor +* @param speed : current device speed +* @param length : pointer to data length variable +* @retval pointer to descriptor buffer +*/ +uint8_t * USBD_MSC_InterfaceStrDescriptor( uint8_t speed , uint16_t *length) +{ + if(speed == 0) + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc_MSC, length); + } + else + { + USBD_GetString((uint8_t *)(uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc_MSC, length); + } + return USBD_StrDesc_MSC; +} + +/** + * @brief Create the serial number string descriptor + * @param None + * @retval None + */ +static void Get_SerialNum(void) +{ + uint32_t deviceserial0, deviceserial1, deviceserial2; + + deviceserial0 = *(uint32_t*)DEVICE_ID1; + deviceserial1 = *(uint32_t*)DEVICE_ID2; + deviceserial2 = *(uint32_t*)DEVICE_ID3; + + deviceserial0 += deviceserial2; + + if (deviceserial0 != 0) + { + IntToUnicode (deviceserial0, &USBD_StringSerial_MSC[2] ,8); + IntToUnicode (deviceserial1, &USBD_StringSerial_MSC[18] ,4); + } +} + +/** + * @brief Convert Hex 32Bits value into char + * @param value: value to convert + * @param pbuf: pointer to the buffer + * @param len: buffer length + * @retval None + */ +static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2* idx] = (value >> 28) + '0'; + } + else + { + pbuf[2* idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[ 2* idx + 1] = 0; + } +} + + +/** + * @} + */ + + +/** + * @} + */ + + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/msc/usbd_msc_desc.h b/src/main/msc/usbd_msc_desc.h new file mode 100644 index 00000000000..03a3d9bbcca --- /dev/null +++ b/src/main/msc/usbd_msc_desc.h @@ -0,0 +1,132 @@ +/** + ****************************************************************************** + * @file usbd_desc.h + * @author MCD Application Team + * @version V1.2.0 + * @date 09-November-2015 + * @brief header file for the usbd_desc.c file + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * 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. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ + +#ifndef __USB_DESC_H +#define __USB_DESC_H + +/* Includes ------------------------------------------------------------------*/ +#include "usbd_req.h" + +/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY + * @{ + */ + +/** @defgroup USB_DESC + * @brief general defines for the usb device library file + * @{ + */ + +/** @defgroup USB_DESC_Exported_Defines + * @{ + */ +#define USB_DEVICE_DESCRIPTOR_TYPE 0x01 +#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02 +#define USB_STRING_DESCRIPTOR_TYPE 0x03 +#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04 +#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05 +#define USB_SIZ_DEVICE_DESC 18 +#define USB_SIZ_STRING_LANGID 4 + +#if !defined (USE_STM3210C_EVAL) +#define DEVICE_ID1 (0x1FFF7A10) +#define DEVICE_ID2 (0x1FFF7A14) +#define DEVICE_ID3 (0x1FFF7A18) + +#else +#define DEVICE_ID1 (0x1FFFF7E8) +#define DEVICE_ID2 (0x1FFFF7EA) +#define DEVICE_ID3 (0x1FFFF7EC) +#endif + +#define USB_SIZ_STRING_SERIAL 0x1A +/** + * @} + */ + + +/** @defgroup USBD_DESC_Exported_TypesDefinitions + * @{ + */ +/** + * @} + */ + + + +/** @defgroup USBD_DESC_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup USBD_DESC_Exported_Variables + * @{ + */ +extern uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC]; +extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ]; +extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; +extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]; +extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID]; +extern USBD_DEVICE USR_desc; +/** + * @} + */ + +/** @defgroup USBD_DESC_Exported_FunctionsPrototype + * @{ + */ + + +uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_ProductStrDescriptor ( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length); + +#ifdef USB_SUPPORT_USER_STRING_DESC +uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length); +#endif /* USB_SUPPORT_USER_STRING_DESC */ + +/** + * @} + */ + +#endif /* __USBD_DESC_H */ + +/** + * @} + */ + +/** +* @} +*/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/msc/usbd_storage.c b/src/main/msc/usbd_storage.c new file mode 100644 index 00000000000..43121206996 --- /dev/null +++ b/src/main/msc/usbd_storage.c @@ -0,0 +1,38 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: jflyper (https://github.com/jflyper) + */ + +#ifdef USE_HAL_DRIVER +#include "usbd_msc.h" +#else +#include "usbd_msc_mem.h" +#include "usbd_msc_core.h" +#endif + +#include "usbd_storage.h" + +#ifdef USE_HAL_DRIVER +USBD_StorageTypeDef *USBD_STORAGE_fops; +#else +USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops; +#endif diff --git a/src/main/msc/usbd_storage.h b/src/main/msc/usbd_storage.h new file mode 100644 index 00000000000..3fb51e3e221 --- /dev/null +++ b/src/main/msc/usbd_storage.h @@ -0,0 +1,46 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ +/* + * Author: Chris Hockuba (https://github.com/conkerkh) + */ + +#pragma once + +#ifdef USE_HAL_DRIVER +#include "usbd_msc.h" +#else +#include "usbd_msc_mem.h" +#include "usbd_msc_core.h" +#endif + +#ifdef USE_HAL_DRIVER +extern USBD_StorageTypeDef *USBD_STORAGE_fops; +#ifdef USE_SDCARD +extern USBD_StorageTypeDef USBD_MSC_MICRO_SDIO_fops; +#endif +#ifdef USE_FLASHFS +extern USBD_StorageTypeDef USBD_MSC_EMFAT_fops; +#endif +#else +extern USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops; +#ifdef USE_SDCARD +extern USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops; +#endif +#ifdef USE_FLASHFS +extern USBD_STORAGE_cb_TypeDef USBD_MSC_EMFAT_fops; +#endif +#endif diff --git a/src/main/msc/usbd_storage_emfat.c b/src/main/msc/usbd_storage_emfat.c new file mode 100644 index 00000000000..096cf8a4b37 --- /dev/null +++ b/src/main/msc/usbd_storage_emfat.c @@ -0,0 +1,154 @@ +/* + * Derived from github.com/fetisov/emfat/project/StorageMode.c + */ + +/* + * The MIT License (MIT) + * + * Copyright (c) 2015 by Sergey Fetisov + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#include + +#include "platform.h" + +#include "common/utils.h" + +#include "drivers/light_led.h" +#include "drivers/time.h" +#include "drivers/flash.h" + +#include "io/flashfs.h" + +#include "usbd_storage.h" +#include "usbd_storage_emfat.h" +#include "emfat_file.h" + + +#define STORAGE_LUN_NBR 1 + +static const uint8_t STORAGE_Inquirydata[] = +{ + 0x00, 0x80, 0x02, 0x02, +#ifdef USE_HAL_DRIVER + (STANDARD_INQUIRY_DATA_LEN - 5), +#else + (USBD_STD_INQUIRY_LENGTH - 5), +#endif + 0x00, 0x00, 0x00, + 'B', 'E', 'T', 'A', 'F', 'L', 'T', ' ', // Manufacturer : 8 bytes + 'O', 'n', 'b', 'o', 'a', 'r', 'd', ' ', // Product : 16 Bytes + 'F', 'l', 'a', 's', 'h', ' ', ' ', ' ', // + ' ', ' ', ' ' ,' ', // Version : 4 Bytes +}; + +static int8_t STORAGE_Init(uint8_t lun) +{ + UNUSED(lun); + + LED0_ON; + +#ifdef USE_FLASHFS +#ifdef USE_FLASH + flashInit(flashConfig()); +#endif + flashfsInit(); +#endif + emfat_init_files(); + + delay(1000); + + LED0_OFF; + + return 0; +} + +#ifdef USE_HAL_DRIVER +static int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint16_t *block_size) +#else +static int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size) +#endif +{ + UNUSED(lun); + *block_size = 512; + *block_num = emfat.disk_sectors; + return 0; +} + +static int8_t STORAGE_IsReady(uint8_t lun) +{ + UNUSED(lun); + return 0; +} + +static int8_t STORAGE_IsWriteProtected(uint8_t lun) +{ + UNUSED(lun); + return 1; +} + +static int8_t STORAGE_Read( + uint8_t lun, // logical unit number + uint8_t *buf, // Pointer to the buffer to save data + uint32_t blk_addr, // address of 1st block to be read + uint16_t blk_len) // nmber of blocks to be read +{ + UNUSED(lun); + LED0_ON; + emfat_read(&emfat, buf, blk_addr, blk_len); + LED0_OFF; + return 0; +} + +static int8_t STORAGE_Write(uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len) +{ + UNUSED(lun); + UNUSED(buf); + UNUSED(blk_addr); + UNUSED(blk_len); + + return 1; +} + +static int8_t STORAGE_GetMaxLun(void) +{ + return (STORAGE_LUN_NBR - 1); +} + +#ifdef USE_HAL_DRIVER +USBD_StorageTypeDef +#else +USBD_STORAGE_cb_TypeDef +#endif +USBD_MSC_EMFAT_fops = +{ + STORAGE_Init, + STORAGE_GetCapacity, + STORAGE_IsReady, + STORAGE_IsWriteProtected, + STORAGE_Read, + STORAGE_Write, + STORAGE_GetMaxLun, + (int8_t *)STORAGE_Inquirydata, +}; diff --git a/src/main/msc/usbd_storage_emfat.h b/src/main/msc/usbd_storage_emfat.h new file mode 100644 index 00000000000..e91ead310b9 --- /dev/null +++ b/src/main/msc/usbd_storage_emfat.h @@ -0,0 +1,25 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + * + * Author: jflyper (https://github.com/jflyper) + * + */ + +#pragma once + +#include "emfat.h" + +extern emfat_t emfat; diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c new file mode 100644 index 00000000000..32ca97629b5 --- /dev/null +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -0,0 +1,257 @@ +/** + ****************************************************************************** + * @file usbd_storage_template.c + * @author MCD Application Team + * @version V1.2.0 + * @date 09-November-2015 + * @brief Memory management layer + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * 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. + * + ****************************************************************************** + */ + + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +#include "platform.h" +#include "common/utils.h" + +#include "usbd_storage.h" + +#include "drivers/sdcard.h" +#include "drivers/light_led.h" +#include "drivers/io.h" +#include "drivers/bus_spi.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Extern function prototypes ------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/* USB NVIC Priority has to be lower than both DMA and SDIO priority, + * otherwise SDIO won't be able to preempt USB. + */ + +#define STORAGE_LUN_NBR 1 +#define STORAGE_BLK_NBR 0x10000 +#define STORAGE_BLK_SIZ 0x200 + +static int8_t STORAGE_Init (uint8_t lun); + +#ifdef USE_HAL_DRIVER +static int8_t STORAGE_GetCapacity (uint8_t lun, + uint32_t *block_num, + uint16_t *block_size); +#else +static int8_t STORAGE_GetCapacity (uint8_t lun, + uint32_t *block_num, + uint32_t *block_size); +#endif + +static int8_t STORAGE_IsReady (uint8_t lun); + +static int8_t STORAGE_IsWriteProtected (uint8_t lun); + +static int8_t STORAGE_Read (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len); + +static int8_t STORAGE_Write (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len); + +static int8_t STORAGE_GetMaxLun (void); + +/* USB Mass storage Standard Inquiry Data */ +static uint8_t STORAGE_Inquirydata[] = {//36 + + /* LUN 0 */ + 0x00, + 0x80, + 0x02, + 0x02, +#ifdef USE_HAL_DRIVER + (STANDARD_INQUIRY_DATA_LEN - 5), +#else + (USBD_STD_INQUIRY_LENGTH - 5), +#endif + 0x00, + 0x00, + 0x00, + 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */ + 'P', 'r', 'o', 'd', 'u', 't', ' ', ' ', /* Product : 16 Bytes */ + ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ', + '0', '.', '0' ,'1', /* Version : 4 Bytes */ +}; + +#ifdef USE_HAL_DRIVER +USBD_StorageTypeDef USBD_MSC_MICRO_SDIO_fops = +{ + STORAGE_Init, + STORAGE_GetCapacity, + STORAGE_IsReady, + STORAGE_IsWriteProtected, + STORAGE_Read, + STORAGE_Write, + STORAGE_GetMaxLun, + (int8_t*)STORAGE_Inquirydata, +}; +#else +USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops = +{ + STORAGE_Init, + STORAGE_GetCapacity, + STORAGE_IsReady, + STORAGE_IsWriteProtected, + STORAGE_Read, + STORAGE_Write, + STORAGE_GetMaxLun, + (int8_t*)STORAGE_Inquirydata, +}; +#endif + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the microSD card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Init (uint8_t lun) +{ + UNUSED(lun); + LED0_OFF; + sdcard_init(false); + while (sdcard_poll() == 0); + LED0_ON; + return 0; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +#ifdef USE_HAL_DRIVER +static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint16_t *block_size) +#else +static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint32_t *block_size) +#endif +{ + UNUSED(lun); + *block_num = sdcard_getMetadata()->numBlocks; + *block_size = 512; + return (0); +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_IsReady (uint8_t lun) +{ + UNUSED(lun); + int8_t ret = -1; + if (sdcard_poll()) { + ret = 0; + } + return ret; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_IsWriteProtected (uint8_t lun) +{ + UNUSED(lun); + return 0; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Read (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len) +{ + UNUSED(lun); + LED1_ON; + for (int i = 0; i < blk_len; i++) { + while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, NULL) == 0); + while (sdcard_poll() == 0); + } + LED1_OFF; + return 0; +} +/******************************************************************************* +* Function Name : Write_Memory +* Description : Handle the Write operation to the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Write (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len) +{ + UNUSED(lun); + LED1_ON; + for (int i = 0; i < blk_len; i++) { + while (sdcard_writeBlock(blk_addr + i, buf + (i * 512), NULL, NULL) != SDCARD_OPERATION_IN_PROGRESS) { + sdcard_poll(); + } + while (sdcard_poll() == 0); + } + LED1_OFF; + return 0; +} +/******************************************************************************* +* Function Name : Write_Memory +* Description : Handle the Write operation to the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_GetMaxLun (void) +{ + return (STORAGE_LUN_NBR - 1); +} + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/msc/usbd_storage_sdio.c b/src/main/msc/usbd_storage_sdio.c new file mode 100644 index 00000000000..00f9c565321 --- /dev/null +++ b/src/main/msc/usbd_storage_sdio.c @@ -0,0 +1,285 @@ +/** + ****************************************************************************** + * @file usbd_storage_template.c + * @author MCD Application Team + * @version V1.2.0 + * @date 09-November-2015 + * @brief Memory management layer + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * 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. + * + ****************************************************************************** + */ + + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +#include "platform.h" + +#include "drivers/sdmmc_sdio.h" +#include "drivers/light_led.h" +#include "drivers/io.h" +#include "common/utils.h" + +#ifdef USE_HAL_DRIVER +#include "usbd_msc.h" +#else +#include "usbd_msc_mem.h" +#include "usbd_msc_core.h" +#endif + +#include "usbd_storage.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Extern function prototypes ------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/* USB NVIC Priority has to be lower than both DMA and SDIO priority, + * otherwise SDIO won't be able to preempt USB. + */ + +#define STORAGE_LUN_NBR 1 +#define STORAGE_BLK_NBR 0x10000 +#define STORAGE_BLK_SIZ 0x200 + +static int8_t STORAGE_Init (uint8_t lun); + +#ifdef USE_HAL_DRIVER +static int8_t STORAGE_GetCapacity (uint8_t lun, + uint32_t *block_num, + uint16_t *block_size); +#else +static int8_t STORAGE_GetCapacity (uint8_t lun, + uint32_t *block_num, + uint32_t *block_size); +#endif + +static int8_t STORAGE_IsReady (uint8_t lun); + +static int8_t STORAGE_IsWriteProtected (uint8_t lun); + +static int8_t STORAGE_Read (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len); + +static int8_t STORAGE_Write (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len); + +static int8_t STORAGE_GetMaxLun (void); + +/* USB Mass storage Standard Inquiry Data */ +static uint8_t STORAGE_Inquirydata[] = {//36 + + /* LUN 0 */ + 0x00, + 0x80, + 0x02, + 0x02, +#ifdef USE_HAL_DRIVER + (STANDARD_INQUIRY_DATA_LEN - 5), +#else + (USBD_STD_INQUIRY_LENGTH - 5), +#endif + 0x00, + 0x00, + 0x00, + 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */ + 'P', 'r', 'o', 'd', 'u', 't', ' ', ' ', /* Product : 16 Bytes */ + ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ', + '0', '.', '0' ,'1', /* Version : 4 Bytes */ +}; + +#ifdef USE_HAL_DRIVER +USBD_StorageTypeDef USBD_MSC_MICRO_SDIO_fops = +{ + STORAGE_Init, + STORAGE_GetCapacity, + STORAGE_IsReady, + STORAGE_IsWriteProtected, + STORAGE_Read, + STORAGE_Write, + STORAGE_GetMaxLun, + (int8_t*)STORAGE_Inquirydata, +}; +#else +USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops = +{ + STORAGE_Init, + STORAGE_GetCapacity, + STORAGE_IsReady, + STORAGE_IsWriteProtected, + STORAGE_Read, + STORAGE_Write, + STORAGE_GetMaxLun, + (int8_t*)STORAGE_Inquirydata, +}; +#endif + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the microSD card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Init (uint8_t lun) +{ + //Initialize SD_DET +#ifdef SDCARD_DETECT_PIN + const IO_t sd_det = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); + IOInit(sd_det, OWNER_SDCARD_DETECT, 0); + IOConfigGPIO(sd_det, IOCFG_IPU); +#endif + + UNUSED(lun); + LED0_OFF; + SD_Initialize_LL(SDIO_DMA); + if (SD_Init() != 0) return 1; + LED0_ON; + return 0; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +#ifdef USE_HAL_DRIVER +static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint16_t *block_size) +#else +static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint32_t *block_size) +#endif +{ + UNUSED(lun); + if (SD_IsDetected() == 0) { + return -1; + } + SD_GetCardInfo(); + + *block_num = SD_CardInfo.CardCapacity; + *block_size = 512; + return (0); +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_IsReady (uint8_t lun) +{ + UNUSED(lun); + int8_t ret = -1; + if (SD_GetState() == true && SD_IsDetected() == SD_PRESENT) { + ret = 0; + } + return ret; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_IsWriteProtected (uint8_t lun) +{ + UNUSED(lun); + return 0; +} + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Read (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len) +{ + UNUSED(lun); + if (SD_IsDetected() == 0) { + return -1; + } + LED1_ON; + //buf should be 32bit aligned, but usually is so we don't do byte alignment + if (SD_ReadBlocks_DMA(blk_addr, (uint32_t*) buf, 512, blk_len) == 0) { + while (SD_CheckRead()); + while(SD_GetState() == false); + LED1_OFF; + return 0; + } + LED1_OFF; + return -1; +} +/******************************************************************************* +* Function Name : Write_Memory +* Description : Handle the Write operation to the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_Write (uint8_t lun, + uint8_t *buf, + uint32_t blk_addr, + uint16_t blk_len) +{ + UNUSED(lun); + if (SD_IsDetected() == 0) { + return -1; + } + LED1_ON; + //buf should be 32bit aligned, but usually is so we don't do byte alignment + if (SD_WriteBlocks_DMA(blk_addr, (uint32_t*) buf, 512, blk_len) == 0) { + while (SD_CheckWrite()); + while(SD_GetState() == false); + LED1_OFF; + return 0; + } + LED1_OFF; + return -1; +} +/******************************************************************************* +* Function Name : Write_Memory +* Description : Handle the Write operation to the STORAGE card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static int8_t STORAGE_GetMaxLun (void) +{ + return (STORAGE_LUN_NBR - 1); +} + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/target/common.h b/src/main/target/common.h index 97d92fcf5cf..f2367dca406 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -40,6 +40,11 @@ #define ADC_AVERAGE_N_SAMPLES 20 #endif +// USB_MSC uses 9K of flash, we can't afford that on F3 +#if defined(STM32F4) || defined(STM32F7) +#define USE_USB_MSC +#endif + #define USE_64BIT_TIME #define USE_BLACKBOX #define USE_GPS diff --git a/src/main/vcp_hal/usbd_conf.h b/src/main/vcp_hal/usbd_conf.h index 086de15e944..aaef99aaf48 100644 --- a/src/main/vcp_hal/usbd_conf.h +++ b/src/main/vcp_hal/usbd_conf.h @@ -60,12 +60,13 @@ /* Exported types ------------------------------------------------------------*/ /* Exported constants --------------------------------------------------------*/ /* Common Config */ -#define USBD_MAX_NUM_INTERFACES 0 +#define USBD_MAX_NUM_INTERFACES 3 #define USBD_MAX_NUM_CONFIGURATION 1 #define USBD_MAX_STR_DESC_SIZ 0x100 #define USBD_SUPPORT_USER_STRING 0 #define USBD_SELF_POWERED 1 #define USBD_DEBUG_LEVEL 0 +#define MSC_MEDIA_PACKET 512 #define USE_USB_FS /* Exported macro ------------------------------------------------------------*/ diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index ef34a0932b9..e7eb0c4a982 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -114,6 +114,34 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = { USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */ }; /* USB_DeviceDescriptor */ +#ifdef USE_USB_MSC + +#define USBD_PID_MSC 22314 + +__ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = +{ + 0x12, /*bLength */ + USB_DESC_TYPE_DEVICE, /*bDescriptorType*/ + 0x00, /*bcdUSB */ + 0x02, + 0x00, /*bDeviceClass*/ + 0x00, /*bDeviceSubClass*/ + 0x00, /*bDeviceProtocol*/ + USB_MAX_EP0_SIZE, /*bMaxPacketSize*/ + LOBYTE(USBD_VID), /*idVendor*/ + HIBYTE(USBD_VID), /*idVendor*/ + LOBYTE(USBD_PID_MSC), /*idProduct*/ + HIBYTE(USBD_PID_MSC), /*idProduct*/ + 0x00, /*bcdDevice rel. 2.00*/ + 0x02, + USBD_IDX_MFC_STR, /*Index of manufacturer string*/ + USBD_IDX_PRODUCT_STR, /*Index of product string*/ + USBD_IDX_SERIAL_STR, /*Index of serial number string*/ + USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/ +}; +#endif + + /* USB Standard Device Descriptor */ #if defined ( __ICCARM__ ) /*!< IAR Compiler */ #pragma data_alignment=4 @@ -149,6 +177,12 @@ static void Get_SerialNum(void); uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) { (void)speed; +#ifdef USE_USB_MSC + if (mscCheckBoot()) { + *length = sizeof(USBD_MSC_DeviceDesc); + return USBD_MSC_DeviceDesc; + } +#endif *length = sizeof(USBD_DeviceDesc); return (uint8_t*)USBD_DeviceDesc; } diff --git a/src/main/vcpf4/usbd_conf.h b/src/main/vcpf4/usbd_conf.h index 1978c8d9572..9ece6c3da54 100644 --- a/src/main/vcpf4/usbd_conf.h +++ b/src/main/vcpf4/usbd_conf.h @@ -31,7 +31,7 @@ */ #define USBD_CFG_MAX_NUM 1 #define USBD_ITF_MAX_NUM 1 -#define USB_MAX_STR_DESC_SIZ 50 +#define USB_MAX_STR_DESC_SIZ 255 /** @defgroup USB_VCP_Class_Layer_Parameter * @{ @@ -40,6 +40,9 @@ #define CDC_OUT_EP 0x01 /* EP1 for data OUT */ #define CDC_CMD_EP 0x82 /* EP2 for CDC commands */ +#define HID_IN_EP 0x83 +#define HID_IN_PACKET 8 + /* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */ #ifdef USE_USB_OTG_HS #define CDC_DATA_MAX_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */ @@ -59,6 +62,23 @@ #define APP_TX_DATA_SIZE 2048 /* total size of the OUT (inbound to FC) buffer */ #endif /* USE_USB_OTG_HS */ +/* MSC */ +#define MSC_IN_EP 0x81 +#define MSC_OUT_EP 0x01 +#ifdef USE_USB_OTG_HS +#ifdef USE_ULPI_PHY +#define MSC_MAX_PACKET 512 +#else +#define MSC_MAX_PACKET 64 +#endif +#else /*USE_USB_OTG_FS*/ +#define MSC_MAX_PACKET 64 +#endif + + +#define MSC_MEDIA_PACKET 4096 +/* END MSC */ + #define APP_FOPS VCP_fops /** * @} @@ -97,4 +117,3 @@ #endif //__USBD_CONF__H__ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/src/main/vcpf4/usbd_desc.h b/src/main/vcpf4/usbd_desc.h index 30c6f9789a5..90aa0a87f0a 100644 --- a/src/main/vcpf4/usbd_desc.h +++ b/src/main/vcpf4/usbd_desc.h @@ -77,6 +77,13 @@ extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]; extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID]; extern USBD_DEVICE USR_desc; + +extern uint8_t USBD_DeviceDesc_MSC [USB_SIZ_DEVICE_DESC]; +extern uint8_t USBD_StrDesc_MSC[USB_MAX_STR_DESC_SIZ]; +extern uint8_t USBD_OtherSpeedCfgDesc_MSC[USB_LEN_CFG_DESC]; +extern uint8_t USBD_DeviceQualifierDesc_MSC[USB_LEN_DEV_QUALIFIER_DESC]; +extern uint8_t USBD_LangIDDesc_MSC[USB_SIZ_STRING_LANGID]; +extern USBD_DEVICE MSC_desc; /** * @} */ @@ -94,6 +101,14 @@ uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_DeviceDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_LangIDStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_ProductStrDescriptor ( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_SerialStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_ConfigStrDescriptor( uint8_t speed , uint16_t *length); +uint8_t * USBD_MSC_InterfaceStrDescriptor( uint8_t speed , uint16_t *length); + #ifdef USB_SUPPORT_USER_STRING_DESC uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length); #endif /* USB_SUPPORT_USER_STRING_DESC */ From 6049f06ae8dad90b50b87092a2e547b4491f9978 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 1 Feb 2019 14:52:26 +0000 Subject: [PATCH 002/110] update for 2.1 dev --- src/main/fc/cli.c | 293 +++++++++++++---------------- src/main/msc/usbd_storage_sd_spi.c | 2 +- src/main/target/common.h | 74 +++++--- 3 files changed, 185 insertions(+), 184 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 5ddbc56388f..7044caf12d7 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -66,6 +66,7 @@ extern uint8_t __config_end; #include "drivers/timer.h" #include "drivers/usb_msc.h" +#include "fc/fc_core.h" #include "fc/cli.h" #include "fc/config.h" #include "fc/controlrate_profile.h" @@ -109,7 +110,7 @@ extern uint8_t __config_end; #include "sensors/opflow.h" #include "sensors/sensors.h" -#include "telemetry/frsky.h" +#include "telemetry/frsky_d.h" #include "telemetry/telemetry.h" #include "build/debug.h" @@ -136,11 +137,9 @@ static void cliAssert(char *cmdline); static void cliBootlog(char *cmdline); #endif -static const char* const emptyName = "-"; - // sync this with features_e static const char * const featureNames[] = { - "RX_PPM", "VBAT", "TX_PROF_SEL", "", "MOTOR_STOP", + "THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP", "", "SOFTSERIAL", "GPS", "", "", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "", @@ -151,7 +150,7 @@ static const char * const featureNames[] = { /* Sensor names (used in lookup tables for *_hardware settings and in status command output) */ // sync with gyroSensor_e -static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"}; +static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"}; // sync this with sensors_e static const char * const sensorTypeNames[] = { @@ -230,11 +229,12 @@ static void cliPutp(void *p, char ch) typedef enum { DUMP_MASTER = (1 << 0), DUMP_PROFILE = (1 << 1), - DUMP_RATES = (1 << 2), - DUMP_ALL = (1 << 3), - DO_DIFF = (1 << 4), - SHOW_DEFAULTS = (1 << 5), - HIDE_UNUSED = (1 << 6) + DUMP_BATTERY_PROFILE = (1 << 2), + DUMP_RATES = (1 << 3), + DUMP_ALL = (1 << 4), + DO_DIFF = (1 << 5), + SHOW_DEFAULTS = (1 << 6), + HIDE_UNUSED = (1 << 7) } dumpFlags_e; static void cliPrintfva(const char *format, va_list va) @@ -330,11 +330,15 @@ static void printValuePointer(const setting_t *var, const void *valuePointer, ui cliPrintf("%s", ftoa(*(float *)valuePointer, buf)); if (full) { if (SETTING_MODE(var) == MODE_DIRECT) { - cliPrintf(" %s", ftoa((float)setting_get_min(var), buf)); - cliPrintf(" %s", ftoa((float)setting_get_max(var), buf)); + cliPrintf(" %s", ftoa((float)settingGetMin(var), buf)); + cliPrintf(" %s", ftoa((float)settingGetMax(var), buf)); } } return; // return from case for float only + + case VAR_STRING: + cliPrintf("%s", (const char *)valuePointer); + return; } switch (SETTING_MODE(var)) { @@ -345,25 +349,28 @@ static void printValuePointer(const setting_t *var, const void *valuePointer, ui cliPrintf("%d", value); if (full) { if (SETTING_MODE(var) == MODE_DIRECT) { - cliPrintf(" %d %u", setting_get_min(var), setting_get_max(var)); + cliPrintf(" %d %u", settingGetMin(var), settingGetMax(var)); } } break; case MODE_LOOKUP: - if (var->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) { - cliPrintf(settingLookupTables[var->config.lookup.tableIndex].values[value]); + { + const char *name = settingLookupValueName(var, value); + if (name) { + cliPrintf(name); } else { - setting_get_name(var, buf); - cliPrintLinef("VALUE %s OUT OF RANGE", buf); + settingGetName(var, buf); + cliPrintLinef("VALUE %d OUT OF RANGE FOR %s", (int)value, buf); } break; } + } } -static bool valuePtrEqualsDefault(uint8_t type, const void *ptr, const void *ptrDefault) +static bool valuePtrEqualsDefault(const setting_t *value, const void *ptr, const void *ptrDefault) { bool result = false; - switch (type & SETTING_TYPE_MASK) { + switch (SETTING_TYPE(value)) { case VAR_UINT8: result = *(uint8_t *)ptr == *(uint8_t *)ptrDefault; break; @@ -387,6 +394,10 @@ static bool valuePtrEqualsDefault(uint8_t type, const void *ptr, const void *ptr case VAR_FLOAT: result = *(float *)ptr == *(float *)ptrDefault; break; + + case VAR_STRING: + result = strncmp(ptr, ptrDefault, settingGetStringMaxLength(value) + 1) == 0; + break; } return result; } @@ -398,14 +409,14 @@ static void dumpPgValue(const setting_t *value, uint8_t dumpMask) const char *defaultFormat = "#set %s = "; // During a dump, the PGs have been backed up to their "copy" // regions and the actual values have been reset to its - // defaults. This means that setting_get_value_pointer() will - // return the default value while setting_get_copy_value_pointer() + // defaults. This means that settingGetValuePointer() will + // return the default value while settingGetCopyValuePointer() // will return the actual value. - const void *valuePointer = setting_get_copy_value_pointer(value); - const void *defaultValuePointer = setting_get_value_pointer(value); - const bool equalsDefault = valuePtrEqualsDefault(value->type, valuePointer, defaultValuePointer); + const void *valuePointer = settingGetCopyValuePointer(value); + const void *defaultValuePointer = settingGetValuePointer(value); + const bool equalsDefault = valuePtrEqualsDefault(value, valuePointer, defaultValuePointer); if (((dumpMask & DO_DIFF) == 0) || !equalsDefault) { - setting_get_name(value, name); + settingGetName(value, name); if (dumpMask & SHOW_DEFAULTS && !equalsDefault) { cliPrintf(defaultFormat, name); printValuePointer(value, defaultValuePointer, 0); @@ -419,8 +430,8 @@ static void dumpPgValue(const setting_t *value, uint8_t dumpMask) static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask) { - for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { - const setting_t *value = &settingsTable[i]; + for (unsigned i = 0; i < SETTINGS_TABLE_COUNT; i++) { + const setting_t *value = settingGet(i); bufWriterFlush(cliWriter); if (SETTING_SECTION(value) == valueSection) { dumpPgValue(value, dumpMask); @@ -430,7 +441,7 @@ static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask) static void cliPrintVar(const setting_t *var, uint32_t full) { - const void *ptr = setting_get_value_pointer(var); + const void *ptr = settingGetValuePointer(var); printValuePointer(var, ptr, full); } @@ -438,11 +449,16 @@ static void cliPrintVar(const setting_t *var, uint32_t full) static void cliPrintVarRange(const setting_t *var) { switch (SETTING_MODE(var)) { - case (MODE_DIRECT): - cliPrintLinef("Allowed range: %d - %u", setting_get_min(var), setting_get_max(var)); + case MODE_DIRECT: + if (SETTING_TYPE(var) == VAR_STRING) { + cliPrintLinef("Max. length: %u", settingGetStringMaxLength(var)); + break; + } + cliPrintLinef("Allowed range: %d - %u", settingGetMin(var), settingGetMax(var)); break; - case (MODE_LOOKUP): { - const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex]; + case MODE_LOOKUP: + { + const lookupTableEntry_t *tableEntry = settingLookupTable(var); cliPrint("Allowed values:"); for (uint32_t i = 0; i < tableEntry->valueCount ; i++) { if (i > 0) @@ -451,7 +467,7 @@ static void cliPrintVarRange(const setting_t *var) } cliPrintLinefeed(); } - break; + break; } } @@ -461,9 +477,9 @@ typedef union { float float_value; } int_float_value_t; -static void cliSetVar(const setting_t *var, const int_float_value_t value) +static void cliSetIntFloatVar(const setting_t *var, const int_float_value_t value) { - void *ptr = setting_get_value_pointer(var); + void *ptr = settingGetValuePointer(var); switch (SETTING_TYPE(var)) { case VAR_UINT8: @@ -483,6 +499,10 @@ static void cliSetVar(const setting_t *var, const int_float_value_t value) case VAR_FLOAT: *(float *)ptr = (float)value.float_value; break; + + case VAR_STRING: + // Handled by cliSet directly + break; } } @@ -729,7 +749,7 @@ static void cliSerial(char *cmdline) ptr = nextArg(ptr); if (ptr) { val = fastA2I(ptr); - portConfig.functionMask = val & 0xFFFF; + portConfig.functionMask = val & 0xFFFFFFFF; validArgumentCount++; } @@ -1248,7 +1268,7 @@ static void cliModeColor(char *cmdline) static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam) { // print out servo settings - const char *format = "servo %u %d %d %d %d "; + const char *format = "servo %u %d %d %d %d"; for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { const servoParam_t *servoConf = &servoParam[i]; bool equalsDefault = false; @@ -1274,25 +1294,6 @@ static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const s servoConf->rate ); } - - // print servo directions - if (defaultServoParam) { - for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { - const servoParam_t *servoConf = &servoParam[i]; - const servoParam_t *servoConfDefault = &defaultServoParam[i]; - bool equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources; - for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) { - equalsDefault = ~(servoConf->reversedSources ^ servoConfDefault->reversedSources) & (1 << channel); - const char *format = "smix reverse %d %d r"; - if (servoConfDefault->reversedSources & (1 << channel)) { - cliDefaultPrintLinef(dumpMask, equalsDefault, format, i , channel); - } - if (servoConf->reversedSources & (1 << channel)) { - cliDumpPrintLinef(dumpMask, equalsDefault, format, i , channel); - } - } - } - } } static void cliServo(char *cmdline) @@ -1411,51 +1412,6 @@ static void cliServoMix(char *cmdline) } else if (sl_strncasecmp(cmdline, "reset", 5) == 0) { // erase custom mixer pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER); - for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { - servoParamsMutable(i)->reversedSources = 0; - } - } else if (sl_strncasecmp(cmdline, "reverse", 7) == 0) { - enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT}; - char *ptr = strchr(cmdline, ' '); - - len = strlen(ptr); - if (len == 0) { - cliPrintf("s"); - for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++) - cliPrintf("\ti%d", inputSource); - cliPrintLinefeed(); - - for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) { - cliPrintf("%d", servoIndex); - for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++) - cliPrintf("\t%s ", (servoParams(servoIndex)->reversedSources & (1 << inputSource)) ? "r" : "n"); - cliPrintLinefeed(); - } - return; - } - - ptr = strtok_r(ptr, " ", &saveptr); - while (ptr != NULL && check < ARGS_COUNT - 1) { - args[check++] = fastA2I(ptr); - ptr = strtok_r(NULL, " ", &saveptr); - } - - if (ptr == NULL || check != ARGS_COUNT - 1) { - cliShowParseError(); - return; - } - - if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS - && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT - && (*ptr == 'r' || *ptr == 'n')) { - if (*ptr == 'r') - servoParamsMutable(args[SERVO])->reversedSources |= 1 << args[INPUT]; - else - servoParamsMutable(args[SERVO])->reversedSources &= ~(1 << args[INPUT]); - } else - cliShowParseError(); - - cliServoMix("reverse"); } else { enum {RULE = 0, TARGET, INPUT, RATE, SPEED, ARGS_COUNT}; char *ptr = strtok_r(cmdline, " ", &saveptr); @@ -2005,15 +1961,7 @@ static void cliRebootEx(bool bootLoader) bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); - stopMotors(); - stopPwmAllMotors(); - - delay(1000); - if (bootLoader) { - systemResetToBootloader(); - return; - } - systemReset(); + fcReboot(bootLoader); } static void cliReboot(void) @@ -2123,24 +2071,6 @@ static void cliMotor(char *cmdline) cliPrintLinef("motor %d: %d", motor_index, motor_disarmed[motor_index]); } -static void printName(uint8_t dumpMask, const systemConfig_t * sConfig) -{ - bool equalsDefault = strlen(sConfig->name) == 0; - cliDumpPrintLinef(dumpMask, equalsDefault, "name %s", equalsDefault ? emptyName : sConfig->name); -} - -static void cliName(char *cmdline) -{ - int32_t len = strlen(cmdline); - if (len > 0) { - memset(systemConfigMutable()->name, 0, ARRAYLEN(systemConfigMutable()->name)); - if (strncmp(cmdline, emptyName, len)) { - strncpy(systemConfigMutable()->name, cmdline, MIN(len, MAX_NAME_LENGTH)); - } - } - printName(DUMP_MASTER, systemConfig()); -} - #ifdef PLAY_SOUND static void cliPlaySound(char *cmdline) { @@ -2204,6 +2134,33 @@ static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask) dumpAllValues(CONTROL_RATE_VALUE, dumpMask); } +static void cliBatteryProfile(char *cmdline) +{ + // CLI profile index is 1-based + if (isEmpty(cmdline)) { + cliPrintLinef("battery_profile %d", getConfigBatteryProfile() + 1); + return; + } else { + const int i = fastA2I(cmdline) - 1; + if (i >= 0 && i < MAX_PROFILE_COUNT) { + setConfigBatteryProfileAndWriteEEPROM(i); + cliBatteryProfile(""); + } + } +} + +static void cliDumpBatteryProfile(uint8_t profileIndex, uint8_t dumpMask) +{ + if (profileIndex >= MAX_BATTERY_PROFILE_COUNT) { + // Faulty values + return; + } + setConfigBatteryProfile(profileIndex); + cliPrintHashLine("battery_profile"); + cliPrintLinef("battery_profile %d\r\n", getConfigBatteryProfile() + 1); + dumpAllValues(BATTERY_CONFIG_VALUE, dumpMask); +} + static void cliSave(char *cmdline) { UNUSED(cmdline); @@ -2232,8 +2189,8 @@ static void cliGet(char *cmdline) char name[SETTING_MAX_NAME_LENGTH]; for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { - val = &settingsTable[i]; - if (setting_name_contains(val, name, cmdline)) { + val = settingGet(i); + if (settingNameContains(val, name, cmdline)) { cliPrintf("%s = ", name); cliPrintVar(val, 0); cliPrintLinefeed(); @@ -2264,8 +2221,8 @@ static void cliSet(char *cmdline) if (len == 0 || (len == 1 && cmdline[0] == '*')) { cliPrintLine("Current settings:"); for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { - val = &settingsTable[i]; - setting_get_name(val, name); + val = settingGet(i); + settingGetName(val, name); cliPrintf("%s = ", name); cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui cliPrintLinefeed(); @@ -2286,19 +2243,23 @@ static void cliSet(char *cmdline) } for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { - val = &settingsTable[i]; + val = settingGet(i); // ensure exact match when setting to prevent setting variables with shorter names - if (setting_name_exact_match(val, name, cmdline, variableNameLength)) { + if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) { + const setting_type_e type = SETTING_TYPE(val); + if (type == VAR_STRING) { + settingSetString(val, eqptr, strlen(eqptr)); + return; + } + const setting_mode_e mode = SETTING_MODE(val); bool changeValue = false; int_float_value_t tmp = {0}; - const int mode = SETTING_MODE(val); - const int type = SETTING_TYPE(val); switch (mode) { case MODE_DIRECT: { if (*eqptr != 0 && strspn(eqptr, "0123456789.+-") == strlen(eqptr)) { float valuef = fastA2F(eqptr); // note: compare float values - if (valuef >= (float)setting_get_min(val) && valuef <= (float)setting_get_max(val)) { + if (valuef >= (float)settingGetMin(val) && valuef <= (float)settingGetMax(val)) { if (type == VAR_FLOAT) tmp.float_value = valuef; @@ -2313,7 +2274,7 @@ static void cliSet(char *cmdline) } break; case MODE_LOOKUP: { - const lookupTableEntry_t *tableEntry = &settingLookupTables[settingsTable[i].config.lookup.tableIndex]; + const lookupTableEntry_t *tableEntry = settingLookupTable(val); bool matched = false; for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) { matched = sl_strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0; @@ -2328,12 +2289,12 @@ static void cliSet(char *cmdline) } if (changeValue) { - cliSetVar(val, tmp); + cliSetIntFloatVar(val, tmp); cliPrintf("%s set to ", name); cliPrintVar(val, 0); } else { - cliPrint("Invalid value."); + cliPrint("Invalid value. "); cliPrintVarRange(val); cliPrintLinefeed(); } @@ -2359,14 +2320,14 @@ static void cliStatus(char *cmdline) { UNUSED(cmdline); - char buf[FORMATTED_DATE_TIME_BUFSIZE]; + char buf[MAX(FORMATTED_DATE_TIME_BUFSIZE, SETTING_MAX_NAME_LENGTH)]; dateTime_t dt; cliPrintLinef("System Uptime: %d seconds", millis() / 1000); rtcGetDateTime(&dt); dateTimeFormatLocal(buf, &dt); cliPrintLinef("Current Time: %s", buf); - cliPrintLinef("Voltage: %d.%dV (%dS battery - %s)", getBatteryVoltage() / 100, getBatteryVoltage() % 100, getBatteryCellCount(), getBatteryStateString()); + cliPrintLinef("Voltage: %d.%02dV (%dS battery - %s)", getBatteryVoltage() / 100, getBatteryVoltage() % 100, getBatteryCellCount(), getBatteryStateString()); cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000)); const uint32_t detectedSensorsMask = sensorsMask(); @@ -2450,11 +2411,7 @@ static void cliStatus(char *cmdline) #endif cliPrintf("System load: %d", averageSystemLoadPercent); -#ifdef USE_ASYNC_GYRO_PROCESSING - const timeDelta_t pidTaskDeltaTime = getTaskDeltaTime(TASK_PID); -#else const timeDelta_t pidTaskDeltaTime = getTaskDeltaTime(TASK_GYROPID); -#endif const int pidRate = pidTaskDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)pidTaskDeltaTime)); const int rxRate = getTaskDeltaTime(TASK_RX) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_RX))); const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM))); @@ -2468,6 +2425,13 @@ static void cliStatus(char *cmdline) if (bitpos > 6) cliPrintf(" %s", armingDisableFlagNames[bitpos - 7]); } cliPrintLinefeed(); + if (armingFlags & ARMING_DISABLED_INVALID_SETTING) { + unsigned invalidIndex; + if (!settingsValidate(&invalidIndex)) { + settingGetName(settingGet(invalidIndex), buf); + cliPrintLinef("Invalid setting: %s", buf); + } + } #else cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS); #endif @@ -2516,6 +2480,9 @@ static void cliVersion(char *cmdline) buildTime, shortGitRevision ); + cliPrintLinef("# GCC-%s", + compilerVersion + ); } static void cliMemory(char *cmdline) @@ -2584,6 +2551,8 @@ static void printConfig(const char *cmdline, bool doDiff) dumpMask = DUMP_MASTER; // only } else if ((options = checkCommand(cmdline, "profile"))) { dumpMask = DUMP_PROFILE; // only + } else if ((options = checkCommand(cmdline, "battery_profile"))) { + dumpMask = DUMP_BATTERY_PROFILE; // only } else if ((options = checkCommand(cmdline, "all"))) { dumpMask = DUMP_ALL; // all profiles and rates } else { @@ -2595,11 +2564,13 @@ static void printConfig(const char *cmdline, bool doDiff) } const int currentProfileIndexSave = getConfigProfile(); + const int currentBatteryProfileIndexSave = getConfigBatteryProfile(); backupConfigs(); // reset all configs to defaults to do differencing resetConfigs(); // restore the profile indices, since they should not be reset for proper comparison setConfigProfile(currentProfileIndexSave); + setConfigBatteryProfile(currentBatteryProfileIndexSave); if (checkCommand(options, "showdefaults")) { dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values @@ -2645,9 +2616,6 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("map"); printMap(dumpMask, &rxConfig_Copy, rxConfig()); - cliPrintHashLine("name"); - printName(dumpMask, &systemConfig_Copy); - cliPrintHashLine("serial"); printSerial(dumpMask, &serialConfig_Copy, serialConfig()); @@ -2682,23 +2650,35 @@ static void printConfig(const char *cmdline, bool doDiff) if (dumpMask & DUMP_ALL) { // dump all profiles const int currentProfileIndexSave = getConfigProfile(); + const int currentBatteryProfileIndexSave = getConfigBatteryProfile(); for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) { cliDumpProfile(ii, dumpMask); } + for (int ii = 0; ii < MAX_BATTERY_PROFILE_COUNT; ++ii) { + cliDumpBatteryProfile(ii, dumpMask); + } setConfigProfile(currentProfileIndexSave); + setConfigBatteryProfile(currentBatteryProfileIndexSave); + cliPrintHashLine("restore original profile selection"); cliPrintLinef("profile %d", currentProfileIndexSave + 1); + cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); cliPrintHashLine("save configuration\r\nsave"); } else { - // dump just the current profile + // dump just the current profiles cliDumpProfile(getConfigProfile(), dumpMask); + cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); } } if (dumpMask & DUMP_PROFILE) { cliDumpProfile(getConfigProfile(), dumpMask); } + + if (dumpMask & DUMP_BATTERY_PROFILE) { + cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); + } // restore configs from copies restoreConfigs(); } @@ -2797,9 +2777,9 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults), CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu), CLI_COMMAND_DEF("diff", "list configuration changes from default", - "[master|profile|rates|all] {showdefaults}", cliDiff), + "[master|battery_profile|profile|rates|all] {showdefaults}", cliDiff), CLI_COMMAND_DEF("dump", "dump configuration", - "[master|profile|rates|all] {showdefaults}", cliDump), + "[master|battery_profile|profile|rates|all] {showdefaults}", cliDump), #ifdef USE_RX_ELERES CLI_COMMAND_DEF("eleres_bind", NULL, NULL, cliEleresBind), #endif // USE_RX_ELERES @@ -2830,12 +2810,13 @@ const clicmd_t cmdTable[] = { #ifdef USE_USB_MSC CLI_COMMAND_DEF("msc", "switch into msc mode", NULL, cliMsc), #endif - CLI_COMMAND_DEF("name", "name of craft", NULL, cliName), #ifdef PLAY_SOUND CLI_COMMAND_DEF("play_sound", NULL, "[]\r\n", cliPlaySound), #endif CLI_COMMAND_DEF("profile", "change profile", "[]", cliProfile), + CLI_COMMAND_DEF("battery_profile", "change battery profile", + "[]", cliBatteryProfile), #if !defined(SKIP_TASK_STATISTICS) && !defined(SKIP_CLI_RESOURCES) CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), #endif @@ -2849,9 +2830,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("set", "change setting", "[=]", cliSet), CLI_COMMAND_DEF("smix", "servo mixer", " \r\n" - "\treset\r\n" - "\tload \r\n" - "\treverse r|n", cliServoMix), + "\treset\r\n", cliServoMix), #ifdef USE_SDCARD CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo), #endif @@ -3015,4 +2994,4 @@ void cliEnter(serialPort_t *serialPort) void cliInit(const serialConfig_t *serialConfig) { UNUSED(serialConfig); -} \ No newline at end of file +} diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index 32ca97629b5..7dc13c35bfc 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -143,7 +143,7 @@ static int8_t STORAGE_Init (uint8_t lun) { UNUSED(lun); LED0_OFF; - sdcard_init(false); + sdcard_init(); while (sdcard_poll() == 0); LED0_ON; return 0; diff --git a/src/main/target/common.h b/src/main/target/common.h index f2367dca406..44f14eb334e 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -17,6 +17,12 @@ #pragma once +#if defined(STM32F3) +#define DYNAMIC_HEAP_SIZE 1024 +#else +#define DYNAMIC_HEAP_SIZE 2048 +#endif + #define I2C1_OVERCLOCK false #define I2C2_OVERCLOCK false #define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week @@ -33,15 +39,15 @@ #if defined(STM32F3) #define USE_UNDERCLOCK +//save flash for F3 targets +#define CLI_MINIMAL_VERBOSITY +#define SKIP_CLI_COMMAND_HELP +#define SKIP_CLI_RESOURCES #endif #if defined(STM32F3) || defined(STM32F4) #define USE_ADC_AVERAGING #define ADC_AVERAGE_N_SAMPLES 20 -#endif - -// USB_MSC uses 9K of flash, we can't afford that on F3 -#if defined(STM32F4) || defined(STM32F7) #define USE_USB_MSC #endif @@ -55,6 +61,7 @@ #define USE_TELEMETRY_FRSKY #define USE_GYRO_BIQUAD_RC_FIR2 +#define USE_MR_BRAKING_MODE #if defined(STM_FAST_TARGET) #define SCHEDULER_DELAY_LIMIT 10 @@ -63,17 +70,42 @@ #endif #if (FLASH_SIZE > 256) +#define USE_EXTENDED_CMS_MENUS #define USE_UAV_INTERCONNECT #define USE_RX_UIB + +// Allow default rangefinders +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_RANGEFINDER_BENEWAKE +#define USE_RANGEFINDER_VL53L0X + +// Allow default optic flow boards +#define USE_OPFLOW +#define USE_OPFLOW_CXOF +#define USE_OPFLOW_MSP + +#define USE_PITOT +#define USE_PITOT_MS4525 + +#define USE_TEMPERATURE_SENSOR +#define USE_TEMPERATURE_LM75 + +#define USE_MSP_DISPLAYPORT +#define USE_DASHBOARD +#define DASHBOARD_ARMED_BITMAP +#define USE_OLED_UG2864 + +#define USE_PWM_DRIVER_PCA9685 + +#define USE_BOOTLOG +#define BOOTLOG_DESCRIPTIONS #endif #if (FLASH_SIZE > 128) #define NAV_FIXED_WING_LANDING -#define AUTOTUNE_FIXED_WING -#define USE_ASYNC_GYRO_PROCESSING +#define USE_AUTOTUNE_FIXED_WING #define USE_DEBUG_TRACE -#define USE_BOOTLOG -#define BOOTLOG_DESCRIPTIONS #define USE_STATS #define USE_GYRO_NOTCH_1 #define USE_GYRO_NOTCH_2 @@ -81,14 +113,8 @@ #define USE_ACC_NOTCH #define USE_CMS #define CMS_MENU_OSD -#define USE_DASHBOARD -#define USE_OLED_UG2864 -#define USE_MSP_DISPLAYPORT -#define DASHBOARD_ARMED_BITMAP #define USE_GPS_PROTO_NMEA -#define USE_GPS_PROTO_I2C_NAV #define USE_GPS_PROTO_NAZA -#define USE_GPS_PROTO_UBLOX_NEO7PLUS #define USE_GPS_PROTO_MTK #define NAV_AUTO_MAG_DECLINATION #define NAV_GPS_GLITCH_DETECTION @@ -106,20 +132,19 @@ #define USE_SERIALRX_XBUS #define USE_SERIALRX_JETIEXBUS #define USE_SERIALRX_CRSF -#define USE_PMW_SERVO_DRIVER +#define USE_PWM_SERVO_DRIVER #define USE_SERIAL_PASSTHROUGH -#define USE_PWM_DRIVER_PCA9685 #define NAV_MAX_WAYPOINTS 60 #define MAX_BOOTLOG_ENTRIES 64 #define USE_RCDEVICE #define USE_PITOT #define USE_PITOT_ADC -//Enable VTX controll -#define VTX_COMMON -#define VTX_CONTROL -#define VTX_SMARTAUDIO -#define VTX_TRAMP +//Enable VTX control +#define USE_VTX_CONTROL +#define USE_VTX_SMARTAUDIO +#define USE_VTX_TRAMP +#define USE_VTX_FFPV //Enable DST calculations #define RTC_AUTOMATIC_DST @@ -127,10 +152,7 @@ #define USE_WIND_ESTIMATOR #else // FLASH_SIZE < 128 -#define CLI_MINIMAL_VERBOSITY + #define SKIP_TASK_STATISTICS -#define SKIP_CLI_COMMAND_HELP -#define SKIP_CLI_RESOURCES -#define NAV_MAX_WAYPOINTS 30 -#define MAX_BOOTLOG_ENTRIES 32 + #endif From 3a47660efba98f2094f090ff3d6e3f3f61ce5473 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 1 Feb 2019 15:00:28 +0000 Subject: [PATCH 003/110] update --- src/main/target/common.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/target/common.h b/src/main/target/common.h index 44f14eb334e..d8bcdcc2beb 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -45,12 +45,11 @@ #define SKIP_CLI_RESOURCES #endif -#if defined(STM32F3) || defined(STM32F4) -#define USE_ADC_AVERAGING -#define ADC_AVERAGE_N_SAMPLES 20 +#if defined(STM32F4) || defined(STM32F7) #define USE_USB_MSC #endif +#define USE_ADC_AVERAGING #define USE_64BIT_TIME #define USE_BLACKBOX #define USE_GPS From 80dc0e1d5a9b4b42671e39df1f535bb63d8d36d0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 17 Oct 2019 19:28:26 +0200 Subject: [PATCH 004/110] Drop yaw_jump_prevention_limit --- src/main/fc/fc_msp.c | 10 +++++----- src/main/fc/settings.yaml | 3 --- src/main/flight/mixer.c | 8 +------- src/main/flight/mixer.h | 1 - src/main/target/FALCORE/config.c | 2 -- 5 files changed, 6 insertions(+), 18 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 0827b838e1a..0a8f9307316 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1165,7 +1165,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, 0); //Legacy, no longer in use async processing value sbufWriteU8(dst, pidProfile()->heading_hold_rate_limit); sbufWriteU8(dst, HEADING_HOLD_ERROR_LPF_FREQ); - sbufWriteU16(dst, mixerConfig()->yaw_jump_prevention_limit); + sbufWriteU16(dst, 0); sbufWriteU8(dst, gyroConfig()->gyro_lpf); sbufWriteU8(dst, accelerometerConfig()->acc_lpf_hz); sbufWriteU8(dst, 0); //reserved @@ -1398,7 +1398,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP2_INAV_MIXER: sbufWriteU8(dst, mixerConfig()->yaw_motor_direction); - sbufWriteU16(dst, mixerConfig()->yaw_jump_prevention_limit); + sbufWriteU16(dst, 0); sbufWriteU8(dst, mixerConfig()->platformType); sbufWriteU8(dst, mixerConfig()->hasFlaps); sbufWriteU16(dst, mixerConfig()->appliedMixerPreset); @@ -2088,10 +2088,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU16(src); //Legacy, no longer in use async processing value pidProfileMutable()->heading_hold_rate_limit = sbufReadU8(src); sbufReadU8(src); //HEADING_HOLD_ERROR_LPF_FREQ - mixerConfigMutable()->yaw_jump_prevention_limit = sbufReadU16(src); + sbufReadU16(src); //Legacy yaw_jump_prevention_limit gyroConfigMutable()->gyro_lpf = sbufReadU8(src); accelerometerConfigMutable()->acc_lpf_hz = sbufReadU8(src); - sbufReadU8(src); //reserved + sbufReadU8(src); //reserved sbufReadU8(src); //reserved sbufReadU8(src); //reserved sbufReadU8(src); //reserved @@ -2733,7 +2733,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_SET_MIXER: mixerConfigMutable()->yaw_motor_direction = sbufReadU8(src); - mixerConfigMutable()->yaw_jump_prevention_limit = sbufReadU16(src); + sbufReadU16(src); // Was yaw_jump_prevention_limit mixerConfigMutable()->platformType = sbufReadU8(src); mixerConfigMutable()->hasFlaps = sbufReadU8(src); mixerConfigMutable()->appliedMixerPreset = sbufReadU16(src); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index dbeb09a5f7f..2d8a46b1fb0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -685,9 +685,6 @@ groups: - name: yaw_motor_direction min: -1 max: 1 - - name: yaw_jump_prevention_limit - min: YAW_JUMP_PREVENTION_LIMIT_LOW - max: YAW_JUMP_PREVENTION_LIMIT_HIGH - name: platform_type field: platformType type: uint8_t diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 36ab742c57e..4b56b582b49 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -70,11 +70,10 @@ PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, .neutral3d = 1460 ); -PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 2); PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, .yaw_motor_direction = 1, - .yaw_jump_prevention_limit = 200, .platformType = PLATFORM_MULTIROTOR, .hasFlaps = false, .appliedMixerPreset = -1, //This flag is not available in CLI and used by Configurator only @@ -291,11 +290,6 @@ void FAST_CODE NOINLINE mixTable(const float dT) input[ROLL] = axisPID[ROLL]; input[PITCH] = axisPID[PITCH]; input[YAW] = axisPID[YAW]; - - if (motorCount >= 4 && mixerConfig()->yaw_jump_prevention_limit < YAW_JUMP_PREVENTION_LIMIT_HIGH) { - // prevent "yaw jump" during yaw correction - input[YAW] = constrain(input[YAW], -mixerConfig()->yaw_jump_prevention_limit - ABS(rcCommand[YAW]), mixerConfig()->yaw_jump_prevention_limit + ABS(rcCommand[YAW])); - } } // Initial mixer concept by bdoiron74 reused and optimized for Air Mode diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 4183ea863d0..eb71c2c4c4a 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -64,7 +64,6 @@ PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); typedef struct mixerConfig_s { int8_t yaw_motor_direction; - uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100) uint8_t platformType; bool hasFlaps; int16_t appliedMixerPreset; diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index 231f0dd6b1b..3924a40085e 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -98,8 +98,6 @@ void targetConfiguration(void) boardAlignmentMutable()->pitchDeciDegrees = 165; boardAlignmentMutable()->yawDeciDegrees = 0; - mixerConfigMutable()->yaw_jump_prevention_limit = 200; - imuConfigMutable()->small_angle = 30; gpsConfigMutable()->provider = GPS_UBLOX; From 0f4a6cfb399508a9958da53e80df92db615b5e66 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 22 Oct 2019 15:46:35 +0200 Subject: [PATCH 005/110] >Drop yaw_p_limit and replace with pidsum_limit_yaq --- docs/Cli.md | 4 ++-- src/main/blackbox/blackbox.c | 2 +- src/main/cms/cms_menu_imu.c | 2 +- src/main/fc/fc_msp.c | 4 ++-- src/main/fc/settings.yaml | 7 ++++--- src/main/flight/pid.c | 31 ++++++++++++++----------------- src/main/flight/pid.h | 14 ++++++-------- src/main/target/FALCORE/config.c | 1 - 8 files changed, 30 insertions(+), 35 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 11c7fd08fca..7e0a0ca48ac 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -423,8 +423,8 @@ A shorter form is also supported to enable and disable functions using `serial < | dyn_notch_q | 120 | Q factor for dynamic notches | | dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | | gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz). Currently experimental | -| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch/Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| yaw_p_limit | 300 | | +| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | | rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | | rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8b103ebb7a8..9b961deac6e 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1679,7 +1679,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", pidBank()->pid[PID_VEL_Z].P, pidBank()->pid[PID_VEL_Z].I, pidBank()->pid[PID_VEL_Z].D); - BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit", "%d", pidProfile()->yaw_p_limit); BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", pidProfile()->yaw_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", pidProfile()->dterm_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz); @@ -1709,6 +1708,7 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("gyro_stage2_lowpass_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%f", (double)pidProfile()->dterm_setpoint_weight); BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit); + BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch); default: diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index 690d5d160da..3b02bb19271 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -404,7 +404,7 @@ static const OSD_Entry cmsx_menuFilterPerProfileEntries[] = OSD_SETTING_ENTRY("DTERM LPF", SETTING_DTERM_LPF_HZ), OSD_SETTING_ENTRY("GYRO SLPF", SETTING_GYRO_LPF_HZ), - OSD_SETTING_ENTRY("YAW P LIM", SETTING_YAW_P_LIMIT), + OSD_SETTING_ENTRY("YAW SUM LIM", SETTING_PIDSUM_LIMIT_YAW), OSD_SETTING_ENTRY("YAW LPF", SETTING_YAW_LPF_HZ), OSD_BACK_AND_END_ENTRY, diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 0a8f9307316..d74b0889008 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1143,7 +1143,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP_PID_ADVANCED: sbufWriteU16(dst, 0); // pidProfile()->rollPitchItermIgnoreRate sbufWriteU16(dst, 0); // pidProfile()->yawItermIgnoreRate - sbufWriteU16(dst, pidProfile()->yaw_p_limit); + sbufWriteU16(dst, 0); //pidProfile()->yaw_p_limit sbufWriteU8(dst, 0); //BF: pidProfile()->deltaMethod sbufWriteU8(dst, 0); //BF: pidProfile()->vbatPidCompensation sbufWriteU8(dst, 0); //BF: pidProfile()->setpointRelaxRatio @@ -2062,7 +2062,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (dataSize >= 17) { sbufReadU16(src); // pidProfileMutable()->rollPitchItermIgnoreRate sbufReadU16(src); // pidProfileMutable()->yawItermIgnoreRate - pidProfileMutable()->yaw_p_limit = sbufReadU16(src); + sbufReadU16(src); //pidProfile()->yaw_p_limit sbufReadU8(src); //BF: pidProfileMutable()->deltaMethod sbufReadU8(src); //BF: pidProfileMutable()->vbatPidCompensation diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2d8a46b1fb0..66270b02766 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1081,9 +1081,10 @@ groups: field: pidSumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - - name: yaw_p_limit - min: YAW_P_LIMIT_MIN - max: YAW_P_LIMIT_MAX + - name: pidsum_limit_yaw + field: pidSumLimitYaw + min: PID_SUM_LIMIT_MIN + max: PID_SUM_LIMIT_MAX - name: iterm_windup field: itermWindupPointPercent min: 0 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 4bcfe5ec1e8..c8d5b55a580 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -94,6 +94,7 @@ typedef struct { pt1Filter_t dBoostLpf; biquadFilter_t dBoostGyroLpf; #endif + uint16_t pidSumLimit; } pidState_t; #ifdef USE_DTERM_NOTCH @@ -136,10 +137,9 @@ static EXTENDED_FASTRAM float dBoostFactor; static EXTENDED_FASTRAM float dBoostMaxAtAlleceleration; #endif -static EXTENDED_FASTRAM uint16_t yawPLimit; static EXTENDED_FASTRAM uint8_t yawLpfHz; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 10); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 11); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -220,13 +220,12 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .axisAccelerationLimitYaw = 10000, // dps/s .axisAccelerationLimitRollPitch = 0, // dps/s - .yaw_p_limit = YAW_P_LIMIT_DEFAULT, - .heading_hold_rate_limit = HEADING_HOLD_RATE_LIMIT_DEFAULT, .max_angle_inclination[FD_ROLL] = 300, // 30 degrees .max_angle_inclination[FD_PITCH] = 300, // 30 degrees .pidSumLimit = PID_SUM_LIMIT_DEFAULT, + .pidSumLimitYaw = PID_SUM_LIMIT_YAW_DEFAULT, .fixedWingItermThrowLimit = FW_ITERM_THROW_LIMIT_DEFAULT, .fixedWingReferenceAirspeed = 1000, @@ -259,12 +258,7 @@ void pidInit(void) itermRelax = pidProfile()->iterm_relax; itermRelaxType = pidProfile()->iterm_relax_type; itermRelaxSetpointThreshold = MC_ITERM_RELAX_SETPOINT_THRESHOLD * MC_ITERM_RELAX_CUTOFF_DEFAULT / pidProfile()->iterm_relax_cutoff; - - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) { - yawPLimit = pidProfile()->yaw_p_limit; - } else { - yawPLimit = 0; - } + yawLpfHz = pidProfile()->yaw_lpf_hz; #ifdef USE_D_BOOST @@ -276,6 +270,14 @@ void pidInit(void) antigravityGain = pidProfile()->antigravityGain; antigravityAccelerator = pidProfile()->antigravityAccelerator; #endif + + for (uint8_t axis = FD_ROLL; axis <= FD_YAW; axis++) { + if (axis == FD_YAW) { + pidState[axis].pidSumLimit = pidProfile()->pidSumLimitYaw; + } else { + pidState[axis].pidSumLimit = pidProfile()->pidSumLimit; + } + } } bool pidInitFilters(void) @@ -593,11 +595,6 @@ static FAST_CODE NOINLINE float pTermProcess(pidState_t *pidState, flight_dynami float newPTerm = rateError * pidState->kP; if (axis == FD_YAW) { - // Constrain YAW by yaw_p_limit value if not servo driven (in that case servo limits apply) - if (yawPLimit) { - newPTerm = constrain(newPTerm, -yawPLimit, yawPLimit); - } - if (yawLpfHz) { newPTerm = pt1FilterApply4(&pidState->ptermLpfState, newPTerm, yawLpfHz, dT); } @@ -631,7 +628,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh } #endif - axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidProfile()->pidSumLimit, +pidProfile()->pidSumLimit); + axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidState->pidSumLimit, +pidState->pidSumLimit); #ifdef USE_BLACKBOX axisPID_P[axis] = newPTerm; @@ -741,7 +738,7 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl // TODO: Get feedback from mixer on available correction range for each axis const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf; - const float newOutputLimited = constrainf(newOutput, -pidProfile()->pidSumLimit, +pidProfile()->pidSumLimit); + const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); // Prevent strong Iterm accumulation during stick inputs const float motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index f98db827896..19b66cd14fc 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -20,13 +20,11 @@ #include "config/parameter_group.h" #include "fc/runtime_config.h" -#define GYRO_SATURATION_LIMIT 1800 // 1800dps -#define PID_SUM_LIMIT_MIN 100 -#define PID_SUM_LIMIT_MAX 1000 -#define PID_SUM_LIMIT_DEFAULT 500 -#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter -#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter -#define YAW_P_LIMIT_DEFAULT 300 // Default value for yaw P limiter +#define GYRO_SATURATION_LIMIT 1800 // 1800dps +#define PID_SUM_LIMIT_MIN 100 +#define PID_SUM_LIMIT_MAX 1000 +#define PID_SUM_LIMIT_DEFAULT 500 +#define PID_SUM_LIMIT_YAW_DEFAULT 400 #define HEADING_HOLD_RATE_LIMIT_MIN 10 #define HEADING_HOLD_RATE_LIMIT_MAX 250 @@ -109,7 +107,6 @@ typedef struct pidProfile_s { uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish uint8_t yaw_lpf_hz; - uint16_t yaw_p_limit; uint8_t heading_hold_rate_limit; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller @@ -122,6 +119,7 @@ typedef struct pidProfile_s { float dterm_setpoint_weight; uint16_t pidSumLimit; + uint16_t pidSumLimitYaw; // Airplane-specific parameters uint16_t fixedWingItermThrowLimit; diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index 3924a40085e..270f27cc499 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -172,7 +172,6 @@ void targetConfiguration(void) pidProfileMutable()->dterm_soft_notch_hz = 0; pidProfileMutable()->dterm_soft_notch_cutoff = 1; pidProfileMutable()->pidSumLimit = 500; - pidProfileMutable()->yaw_p_limit = 300; pidProfileMutable()->axisAccelerationLimitRollPitch = 0; pidProfileMutable()->axisAccelerationLimitYaw = 10000; From 72b140387aa2c1d7d19558459021b1f0069d3f7c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 25 Oct 2019 14:06:24 +0200 Subject: [PATCH 006/110] Drop branching for yaw P filter in favor of function pointer --- src/main/common/filter.c | 8 ++++++++ src/main/common/filter.h | 2 ++ src/main/flight/pid.c | 21 +++++++++++---------- 3 files changed, 21 insertions(+), 10 deletions(-) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index a0c19d20f3b..420ad73a497 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -36,6 +36,14 @@ float nullFilterApply(void *filter, float input) return input; } +float nullFilterApply4(void *filter, float input, float f_cut, float dt) +{ + UNUSED(filter); + UNUSED(f_cut); + UNUSED(dt); + return input; +} + // PT1 Low Pass filter // f_cut = cutoff frequency diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 3ee3d349ebb..3d2cef51208 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -57,8 +57,10 @@ typedef struct firFilter_s { } firFilter_t; typedef float (*filterApplyFnPtr)(void *filter, float input); +typedef float (*filterApply4FnPtr)(void *filter, float input, float f_cut, float dt); float nullFilterApply(void *filter, float input); +float nullFilterApply4(void *filter, float input, float f_cut, float dt); void pt1FilterInit(pt1Filter_t *filter, float f_cut, float dT); void pt1FilterInitRC(pt1Filter_t *filter, float tau, float dT); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index ba72ee4d57e..be63b6b3b40 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -95,6 +95,7 @@ typedef struct { biquadFilter_t dBoostGyroLpf; #endif uint16_t pidSumLimit; + filterApply4FnPtr ptermFilterApplyFn; } pidState_t; #ifdef USE_DTERM_NOTCH @@ -274,8 +275,14 @@ void pidInit(void) for (uint8_t axis = FD_ROLL; axis <= FD_YAW; axis++) { if (axis == FD_YAW) { pidState[axis].pidSumLimit = pidProfile()->pidSumLimitYaw; + if (yawLpfHz) { + pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) pt1FilterApply4; + } else { + pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; + } } else { pidState[axis].pidSumLimit = pidProfile()->pidSumLimit; + pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; } } } @@ -591,22 +598,16 @@ bool isFixedWingItermLimitActive(float stickPosition) return fabsf(stickPosition) > pidProfile()->fixedWingItermLimitOnStickPosition; } -static FAST_CODE NOINLINE float pTermProcess(pidState_t *pidState, flight_dynamics_index_t axis, float rateError, float dT) { +static FAST_CODE NOINLINE float pTermProcess(pidState_t *pidState, float rateError, float dT) { float newPTerm = rateError * pidState->kP; - if (axis == FD_YAW) { - if (yawLpfHz) { - newPTerm = pt1FilterApply4(&pidState->ptermLpfState, newPTerm, yawLpfHz, dT); - } - } - - return newPTerm; + return pidState->ptermFilterApplyFn(&pidState->ptermLpfState, newPTerm, yawLpfHz, dT); } static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { const float rateError = pidState->rateTarget - pidState->gyroRate; - const float newPTerm = pTermProcess(pidState, axis, rateError, dT); + const float newPTerm = pTermProcess(pidState, rateError, dT); const float newFFTerm = pidState->rateTarget * pidState->kFF; // Calculate integral @@ -705,7 +706,7 @@ static float applyDBoost(pidState_t *pidState, flight_dynamics_index_t axis, flo static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { const float rateError = pidState->rateTarget - pidState->gyroRate; - const float newPTerm = pTermProcess(pidState, axis, rateError, dT); + const float newPTerm = pTermProcess(pidState, rateError, dT); // Calculate new D-term float newDTerm; From c538e2eb58d10bcb76d8b4ec4a50808d7c83ccd7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 31 Oct 2019 21:04:05 +0100 Subject: [PATCH 007/110] Cleanup debugs and USE_ defines that are always on --- src/main/build/debug.h | 10 ---- src/main/fc/config.c | 9 ---- src/main/fc/fc_msp.c | 49 ++++-------------- src/main/fc/settings.yaml | 17 ++----- src/main/flight/gyroanalyse.c | 26 ---------- src/main/flight/pid.c | 20 -------- src/main/flight/pid.h | 4 -- src/main/navigation/navigation.c | 3 -- src/main/navigation/navigation_multicopter.c | 4 -- src/main/sensors/acceleration.c | 6 --- src/main/sensors/gyro.c | 52 ++------------------ src/main/target/common.h | 5 -- 12 files changed, 17 insertions(+), 188 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 40c73559f37..8da3ad3f9e1 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -51,29 +51,19 @@ extern timeUs_t sectionTimes[2][4]; typedef enum { DEBUG_NONE, DEBUG_GYRO, - DEBUG_NOTCH, - DEBUG_NAV_LANDING_DETECTOR, - DEBUG_FW_CLIMB_RATE_TO_ALTITUDE, DEBUG_AGL, DEBUG_FLOW_RAW, DEBUG_FLOW, DEBUG_SBUS, DEBUG_FPORT, DEBUG_ALWAYS, - DEBUG_STAGE2, DEBUG_SAG_COMP_VOLTAGE, DEBUG_VIBE, DEBUG_CRUISE, DEBUG_REM_FLIGHT_TIME, DEBUG_SMARTAUDIO, DEBUG_ACC, - DEBUG_GENERIC, DEBUG_ITERM_RELAX, - DEBUG_D_BOOST, - DEBUG_ANTIGRAVITY, - DEBUG_FFT, - DEBUG_FFT_TIME, - DEBUG_FFT_FREQ, DEBUG_ERPM, DEBUG_COUNT } debugType_e; diff --git a/src/main/fc/config.c b/src/main/fc/config.c index bbeeaad4f50..0fac3af42ce 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -167,27 +167,18 @@ uint32_t getLooptime(void) { void validateAndFixConfig(void) { -#ifdef USE_GYRO_NOTCH_1 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) { gyroConfigMutable()->gyro_soft_notch_hz_1 = 0; } -#endif -#ifdef USE_GYRO_NOTCH_2 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) { gyroConfigMutable()->gyro_soft_notch_hz_2 = 0; } -#endif -#ifdef USE_DTERM_NOTCH if (pidProfile()->dterm_soft_notch_cutoff >= pidProfile()->dterm_soft_notch_hz) { pidProfileMutable()->dterm_soft_notch_hz = 0; } -#endif - -#ifdef USE_ACC_NOTCH if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) { accelerometerConfigMutable()->acc_notch_hz = 0; } -#endif // Disable unused features featureClear(FEATURE_UNUSED_3 | FEATURE_UNUSED_4 | FEATURE_UNUSED_5 | FEATURE_UNUSED_6 | FEATURE_UNUSED_7 | FEATURE_UNUSED_8 | FEATURE_UNUSED_9 | FEATURE_UNUSED_10); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 190bc84feb0..ccc95861368 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1101,43 +1101,19 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz); sbufWriteU16(dst, pidProfile()->dterm_lpf_hz); sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); -#ifdef USE_GYRO_NOTCH_1 sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); //masterConfig.gyro_soft_notch_hz_1 sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); //BF: masterConfig.gyro_soft_notch_cutoff_1 -#else - sbufWriteU16(dst, 0); //masterConfig.gyro_soft_notch_hz_1 - sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_1 -#endif -#ifdef USE_DTERM_NOTCH sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); //BF: pidProfile()->dterm_notch_hz sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); //pidProfile()->dterm_notch_cutoff -#else - sbufWriteU16(dst, 0); //BF: pidProfile()->dterm_notch_hz - sbufWriteU16(dst, 1); //pidProfile()->dterm_notch_cutoff -#endif -#ifdef USE_GYRO_NOTCH_2 sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_2); //BF: masterConfig.gyro_soft_notch_hz_2 sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_2); //BF: masterConfig.gyro_soft_notch_cutoff_2 -#else - sbufWriteU16(dst, 0); //BF: masterConfig.gyro_soft_notch_hz_2 - sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2 -#endif -#ifdef USE_ACC_NOTCH sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz); sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); -#else - sbufWriteU16(dst, 0); - sbufWriteU16(dst, 1); -#endif -#ifdef USE_GYRO_BIQUAD_RC_FIR2 sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz); -#else - sbufWriteU16(dst, 0); -#endif break; case MSP_PID_ADVANCED: @@ -2017,43 +1993,38 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) gyroConfigMutable()->gyro_soft_lpf_hz = sbufReadU8(src); pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 255); pidProfileMutable()->yaw_lpf_hz = constrain(sbufReadU16(src), 0, 255); -#ifdef USE_GYRO_NOTCH_1 if (dataSize >= 9) { gyroConfigMutable()->gyro_soft_notch_hz_1 = constrain(sbufReadU16(src), 0, 500); gyroConfigMutable()->gyro_soft_notch_cutoff_1 = constrain(sbufReadU16(src), 1, 500); - } else + } else { return MSP_RESULT_ERROR; -#endif -#ifdef USE_DTERM_NOTCH + } if (dataSize >= 13) { pidProfileMutable()->dterm_soft_notch_hz = constrain(sbufReadU16(src), 0, 500); pidProfileMutable()->dterm_soft_notch_cutoff = constrain(sbufReadU16(src), 1, 500); pidInitFilters(); - } else + } else { return MSP_RESULT_ERROR; -#endif -#ifdef USE_GYRO_NOTCH_2 + } if (dataSize >= 17) { gyroConfigMutable()->gyro_soft_notch_hz_2 = constrain(sbufReadU16(src), 0, 500); gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500); - } else + } else { return MSP_RESULT_ERROR; -#endif + } -#ifdef USE_ACC_NOTCH if (dataSize >= 21) { accelerometerConfigMutable()->acc_notch_hz = constrain(sbufReadU16(src), 0, 255); accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255); - } else + } else { return MSP_RESULT_ERROR; -#endif + } -#ifdef USE_GYRO_BIQUAD_RC_FIR2 if (dataSize >= 22) { gyroConfigMutable()->gyro_stage2_lowpass_hz = constrain(sbufReadU16(src), 0, 500); - } else + } else { return MSP_RESULT_ERROR; -#endif + } } else return MSP_RESULT_ERROR; break; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 835f1331782..2b6cf11bbc3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -78,10 +78,10 @@ tables: - name: i2c_speed values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"] - name: debug_modes - values: ["NONE", "GYRO", "NOTCH", "NAV_LANDING", "FW_ALTITUDE", "AGL", "FLOW_RAW", - "FLOW", "SBUS", "FPORT", "ALWAYS", "STAGE2", "SAG_COMP_VOLTAGE", - "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "GENERIC", "ITERM_RELAX", - "D_BOOST", "ANTIGRAVITY", "FFT", "FFT_TIME", "FFT_FREQ", "ERPM"] + values: ["NONE", "GYRO", "AGL", "FLOW_RAW", + "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", + "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", + "ERPM"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -164,25 +164,20 @@ groups: max: 128 - name: gyro_notch1_hz field: gyro_soft_notch_hz_1 - condition: USE_GYRO_NOTCH_1 max: 500 - name: gyro_notch1_cutoff field: gyro_soft_notch_cutoff_1 - condition: USE_GYRO_NOTCH_1 min: 1 max: 500 - name: gyro_notch2_hz field: gyro_soft_notch_hz_2 - condition: USE_GYRO_NOTCH_2 max: 500 - name: gyro_notch2_cutoff field: gyro_soft_notch_cutoff_2 - condition: USE_GYRO_NOTCH_2 min: 1 max: 500 - name: gyro_stage2_lowpass_hz field: gyro_stage2_lowpass_hz - condition: USE_GYRO_BIQUAD_RC_FIR2 min: 0 max: 500 - name: dyn_notch_width_percent @@ -236,11 +231,9 @@ groups: headers: ["sensors/acceleration.h"] members: - name: acc_notch_hz - condition: USE_ACC_NOTCH min: 0 max: 255 - name: acc_notch_cutoff - condition: USE_ACC_NOTCH min: 1 max: 255 - name: align_acc @@ -1076,12 +1069,10 @@ groups: max: 1 - name: dterm_notch_hz field: dterm_soft_notch_hz - condition: USE_DTERM_NOTCH min: 0 max: 500 - name: dterm_notch_cutoff field: dterm_soft_notch_cutoff - condition: USE_DTERM_NOTCH min: 1 max: 500 - name: pidsum_limit diff --git a/src/main/flight/gyroanalyse.c b/src/main/flight/gyroanalyse.c index 0e387e8cd29..9d61ff72142 100644 --- a/src/main/flight/gyroanalyse.c +++ b/src/main/flight/gyroanalyse.c @@ -157,9 +157,6 @@ void gyroDataAnalyse(gyroAnalyseState_t *state, biquadFilter_t *notchFilterDyn, for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { float sample = state->oversampledGyroAccumulator[axis] * state->maxSampleCountRcp; state->downsampledGyroData[axis][state->circularBufferIdx] = sample; - if (axis == 0) { - DEBUG_SET(DEBUG_FFT, 2, lrintf(sample)); - } state->oversampledGyroAccumulator[axis] = 0; } @@ -201,12 +198,6 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt arm_cfft_instance_f32 *Sint = &(state->fftInstance.Sint); - uint32_t startTime = 0; - if (debugMode == (DEBUG_FFT_TIME)) { - startTime = micros(); - } - - DEBUG_SET(DEBUG_FFT_TIME, 0, state->updateStep); switch (state->updateStep) { case STEP_ARM_CFFT_F32: { @@ -224,14 +215,12 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt arm_radix8_butterfly_f32(state->fftData, FFT_BIN_COUNT, Sint->pTwiddle, 1); break; } - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); break; } case STEP_BITREVERSAL: { // 6us arm_bitreversal_32((uint32_t*) state->fftData, Sint->bitRevLength, Sint->pBitRevTable); - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); state->updateStep++; FALLTHROUGH; } @@ -240,14 +229,12 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt // 14us // this does not work in place => fftData AND rfftData needed stage_rfft_f32(&state->fftInstance, state->fftData, state->rfftData); - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); break; } case STEP_ARM_CMPLX_MAG_F32: { // 8us arm_cmplx_mag_f32(state->rfftData, state->fftData, FFT_BIN_COUNT); - DEBUG_SET(DEBUG_FFT_TIME, 2, micros() - startTime); state->updateStep++; FALLTHROUGH; } @@ -312,15 +299,7 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt dynNotchMaxFFT = MAX(dynNotchMaxFFT, state->centerFreq[state->updateAxis]); - if (state->updateAxis == 0) { - DEBUG_SET(DEBUG_FFT, 3, lrintf(fftMeanIndex * 100)); - DEBUG_SET(DEBUG_FFT_FREQ, 0, state->centerFreq[state->updateAxis]); - } - if (state->updateAxis == 1) { - DEBUG_SET(DEBUG_FFT_FREQ, 1, state->centerFreq[state->updateAxis]); - } // Debug FFT_Freq carries raw gyro, gyro after first filter set, FFT centre for roll and for pitch - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); break; } case STEP_UPDATE_FILTERS: @@ -329,8 +308,6 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt // calculate cutoffFreq and notch Q, update notch filter =1.8+((A2-150)*0.004) if (state->prevCenterFreq[state->updateAxis] != state->centerFreq[state->updateAxis]) { - DEBUG_SET(DEBUG_FFT_FREQ, state->updateAxis + 5, state->centerFreq[state->updateAxis]); - if (dualNotch) { biquadFilterUpdate(¬chFilterDyn[state->updateAxis], state->centerFreq[state->updateAxis] * dynNotch1Ctr, getLooptime(), dynNotchQ, FILTER_NOTCH); biquadFilterUpdate(¬chFilterDyn2[state->updateAxis], state->centerFreq[state->updateAxis] * dynNotch2Ctr, getLooptime(), dynNotchQ, FILTER_NOTCH); @@ -338,7 +315,6 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt biquadFilterUpdate(¬chFilterDyn[state->updateAxis], state->centerFreq[state->updateAxis], getLooptime(), dynNotchQ, FILTER_NOTCH); } } - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); state->updateAxis = (state->updateAxis + 1) % XYZ_AXIS_COUNT; state->updateStep++; @@ -354,8 +330,6 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state, biquadFilt if (state->circularBufferIdx > 0) { arm_mult_f32(&state->downsampledGyroData[state->updateAxis][0], &hanningWindow[ringBufIdx], &state->fftData[ringBufIdx], state->circularBufferIdx); } - - DEBUG_SET(DEBUG_FFT_TIME, 1, micros() - startTime); } } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 5261e4aa427..377bae1d281 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -81,11 +81,8 @@ typedef struct { rateLimitFilter_t axisAccelFilter; pt1Filter_t ptermLpfState; biquadFilter_t deltaLpfState; - // Dterm notch filtering -#ifdef USE_DTERM_NOTCH biquadFilter_t deltaNotchFilter; -#endif float stickPosition; #ifdef USE_D_BOOST @@ -96,10 +93,7 @@ typedef struct { #endif } pidState_t; -#ifdef USE_DTERM_NOTCH STATIC_FASTRAM filterApplyFnPtr notchFilterApplyFn; -#endif - STATIC_FASTRAM bool pidFiltersConfigured = false; FASTRAM float headingHoldCosZLimit; FASTRAM int16_t headingHoldTarget; @@ -310,7 +304,6 @@ bool pidInitFilters(void) firFilterInit(&pidState[axis].gyroRateFilter, pidState[axis].gyroRateBuf, PID_GYRO_RATE_BUF_LENGTH, dtermCoeffs); } -#ifdef USE_DTERM_NOTCH notchFilterApplyFn = nullFilterApply; if (pidProfile()->dterm_soft_notch_hz != 0) { notchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply; @@ -318,7 +311,6 @@ bool pidInitFilters(void) biquadFilterInitNotch(&pidState[axis].deltaNotchFilter, refreshRate, pidProfile()->dterm_soft_notch_hz, pidProfile()->dterm_soft_notch_cutoff); } } -#endif // Init other filters for (int axis = 0; axis < 3; ++ axis) { @@ -682,14 +674,6 @@ static float FAST_CODE applyDBoost(pidState_t *pidState, flight_dynamics_index_t dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT); dBoost = constrainf(dBoost, 1.0f, dBoostFactor); - if (axis == FD_ROLL) { - DEBUG_SET(DEBUG_D_BOOST, 0, dBoostGyroAcceleration); - DEBUG_SET(DEBUG_D_BOOST, 1, dBoostRateAcceleration); - DEBUG_SET(DEBUG_D_BOOST, 2, dBoost * 100); - } else if (axis == FD_PITCH) { - DEBUG_SET(DEBUG_D_BOOST, 3, dBoost * 100); - } - pidState->previousRateTarget = pidState->rateTarget; pidState->previousRateGyro = pidState->gyroRate; } @@ -719,10 +703,8 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl // Calculate delta for Dterm calculation. Apply filters before derivative to minimize effects of dterm kick float deltaFiltered = pidProfile()->dterm_setpoint_weight * pidState->rateTarget - pidState->gyroRate; -#ifdef USE_DTERM_NOTCH // Apply D-term notch deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered); -#endif // Apply additional lowpass if (pidProfile()->dterm_lpf_hz) { @@ -752,8 +734,6 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl #ifdef USE_ANTIGRAVITY const float iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); - DEBUG_SET(DEBUG_ANTIGRAVITY, 0, iTermAntigravityGain * 100); - DEBUG_SET(DEBUG_ANTIGRAVITY, 1, antigravityThrottleHpf); itermErrorRate *= iTermAntigravityGain; #endif diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index ad82f933012..312d19637b9 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -162,11 +162,7 @@ extern int16_t axisPID[]; extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[]; void pidInit(void); - -#ifdef USE_DTERM_NOTCH bool pidInitFilters(void); -#endif - void pidResetErrorAccumulators(void); void pidResetTPAFilter(void); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index d20073bcf6c..b8d1222d005 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2391,9 +2391,6 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAlti // Fixed wing climb rate controller is open-loop. We simply move the known altitude target float timeDelta = US2S(currentTimeUs - lastUpdateTimeUs); - DEBUG_SET(DEBUG_FW_CLIMB_RATE_TO_ALTITUDE, 0, desiredClimbRate); - DEBUG_SET(DEBUG_FW_CLIMB_RATE_TO_ALTITUDE, 1, timeDelta * 1000); - if (timeDelta <= HZ2S(MIN_POSITION_UPDATE_RATE_HZ)) { posControl.desiredState.pos.z += desiredClimbRate * timeDelta; posControl.desiredState.pos.z = constrainf(posControl.desiredState.pos.z, altitudeToUse - 500, altitudeToUse + 500); // FIXME: calculate sanity limits in a smarter way diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 2d4e4f21f85..2c4bca8bb3b 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -660,10 +660,6 @@ bool isMulticopterLandingDetected(void) bool possibleLandingDetected = isAtMinimalThrust && !verticalMovement && !horizontalMovement; - DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 0, isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1); - DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 1, (landingThrSamples == 0) ? 0 : (rcCommandAdjustedThrottle - (landingThrSum / landingThrSamples))); - DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 2, (currentTimeUs - landingTimer) / 1000); - // If we have surface sensor (for example sonar) - use it to detect touchdown if ((posControl.flags.estAglStatus == EST_TRUSTED) && (posControl.actualState.agl.pos.z >= 0)) { // TODO: Come up with a clever way to let sonar increase detection performance, not just add extra safety. diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index f2c3f8b27b5..4a605d8b2f0 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -81,10 +81,8 @@ STATIC_FASTRAM void *accSoftLpfFilter[XYZ_AXIS_COUNT]; STATIC_FASTRAM pt1Filter_t accVibeFloorFilter[XYZ_AXIS_COUNT]; STATIC_FASTRAM pt1Filter_t accVibeFilter[XYZ_AXIS_COUNT]; -#ifdef USE_ACC_NOTCH STATIC_FASTRAM filterApplyFnPtr accNotchFilterApplyFn; STATIC_FASTRAM void *accNotchFilter[XYZ_AXIS_COUNT]; -#endif PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 3); @@ -578,13 +576,11 @@ void accUpdate(void) acc.accADCf[axis] = accSoftLpfFilterApplyFn(accSoftLpfFilter[axis], acc.accADCf[axis]); } -#ifdef USE_ACC_NOTCH if (accelerometerConfig()->acc_notch_hz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { acc.accADCf[axis] = accNotchFilterApplyFn(accNotchFilter[axis], acc.accADCf[axis]); } } -#endif } @@ -665,7 +661,6 @@ void accInitFilters(void) pt1FilterInit(&accVibeFilter[axis], ACC_VIBE_FILT_HZ, accDt); } -#ifdef USE_ACC_NOTCH STATIC_FASTRAM biquadFilter_t accFilterNotch[XYZ_AXIS_COUNT]; accNotchFilterApplyFn = nullFilterApply; @@ -676,7 +671,6 @@ void accInitFilters(void) biquadFilterInitNotch(accNotchFilter[axis], acc.accTargetLooptime, accelerometerConfig()->acc_notch_hz, accelerometerConfig()->acc_notch_cutoff); } } -#endif } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 144921ff5b4..1d76a125d6a 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -84,20 +84,13 @@ STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr softLpfFilterApplyFn; STATIC_FASTRAM void *softLpfFilter[XYZ_AXIS_COUNT]; -#ifdef USE_GYRO_NOTCH_1 STATIC_FASTRAM filterApplyFnPtr notchFilter1ApplyFn; STATIC_FASTRAM void *notchFilter1[XYZ_AXIS_COUNT]; -#endif -#ifdef USE_GYRO_NOTCH_2 STATIC_FASTRAM filterApplyFnPtr notchFilter2ApplyFn; STATIC_FASTRAM void *notchFilter2[XYZ_AXIS_COUNT]; -#endif -#if defined(USE_GYRO_BIQUAD_RC_FIR2) -// gyro biquad RC FIR2 filter STATIC_FASTRAM filterApplyFnPtr gyroFilterStage2ApplyFn; STATIC_FASTRAM void *stage2Filter[XYZ_AXIS_COUNT]; -#endif #ifdef USE_DYNAMIC_FILTERS @@ -337,16 +330,13 @@ void gyroInitFilters(void) { STATIC_FASTRAM filter_t gyroFilterLPF[XYZ_AXIS_COUNT]; softLpfFilterApplyFn = nullFilterApply; -#ifdef USE_GYRO_NOTCH_1 + STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; notchFilter1ApplyFn = nullFilterApply; -#endif -#ifdef USE_GYRO_NOTCH_2 + STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; notchFilter2ApplyFn = nullFilterApply; -#endif - -#ifdef USE_GYRO_BIQUAD_RC_FIR2 + STATIC_FASTRAM biquadFilter_t gyroFilterStage2[XYZ_AXIS_COUNT]; gyroFilterStage2ApplyFn = nullFilterApply; @@ -357,7 +347,6 @@ void gyroInitFilters(void) biquadRCFIR2FilterInit(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); } } -#endif if (gyroConfig()->gyro_soft_lpf_hz) { @@ -380,7 +369,6 @@ void gyroInitFilters(void) } } -#ifdef USE_GYRO_NOTCH_1 if (gyroConfig()->gyro_soft_notch_hz_1) { notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { @@ -388,9 +376,7 @@ void gyroInitFilters(void) biquadFilterInitNotch(notchFilter1[axis], getLooptime(), gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1); } } -#endif -#ifdef USE_GYRO_NOTCH_2 if (gyroConfig()->gyro_soft_notch_hz_2) { notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { @@ -398,7 +384,6 @@ void gyroInitFilters(void) biquadFilterInitNotch(notchFilter2[axis], getLooptime(), gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2); } } -#endif } void gyroStartCalibration(void) @@ -479,44 +464,13 @@ void FAST_CODE NOINLINE gyroUpdate() DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf)); -#ifdef USE_DYNAMIC_FILTERS - if (isDynamicFilterActive()) { - if (axis == FD_ROLL) { - DEBUG_SET(DEBUG_FFT, 0, lrintf(gyroADCf)); - DEBUG_SET(DEBUG_FFT_FREQ, 3, lrintf(gyroADCf)); - } - } -#endif - - if (axis < 2) { - DEBUG_SET(DEBUG_STAGE2, axis, lrintf(gyroADCf)); - } - -#ifdef USE_GYRO_BIQUAD_RC_FIR2 gyroADCf = gyroFilterStage2ApplyFn(stage2Filter[axis], gyroADCf); -#endif - - if (axis < 2) { - DEBUG_SET(DEBUG_STAGE2, axis + 2, lrintf(gyroADCf)); - } - gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf); - - DEBUG_SET(DEBUG_NOTCH, axis, lrintf(gyroADCf)); - -#ifdef USE_GYRO_NOTCH_1 gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf); -#endif -#ifdef USE_GYRO_NOTCH_2 gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf); -#endif #ifdef USE_DYNAMIC_FILTERS if (isDynamicFilterActive()) { - if (axis == FD_ROLL) { - DEBUG_SET(DEBUG_FFT, 1, lrintf(gyroADCf)); - DEBUG_SET(DEBUG_FFT_FREQ, 2, lrintf(gyroADCf)); - } gyroDataAnalysePush(&gyroAnalyseState, axis, gyroADCf); gyroADCf = notchFilterDynApplyFn((filter_t *)¬chFilterDyn[axis], gyroADCf); gyroADCf = notchFilterDynApplyFn2((filter_t *)¬chFilterDyn2[axis], gyroADCf); diff --git a/src/main/target/common.h b/src/main/target/common.h index a5bc99971ad..8f1158ae849 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -54,7 +54,6 @@ #define USE_TELEMETRY_LTM #define USE_TELEMETRY_FRSKY -#define USE_GYRO_BIQUAD_RC_FIR2 #define USE_MR_BRAKING_MODE #if defined(STM_FAST_TARGET) @@ -121,10 +120,6 @@ #define USE_AUTOTUNE_FIXED_WING #define USE_LOG #define USE_STATS -#define USE_GYRO_NOTCH_1 -#define USE_GYRO_NOTCH_2 -#define USE_DTERM_NOTCH -#define USE_ACC_NOTCH #define USE_CMS #define CMS_MENU_OSD #define USE_GPS_PROTO_NMEA From af6d5ee76d54656e232765e0428439aef4f7aecc Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Mon, 18 Nov 2019 22:11:26 +0000 Subject: [PATCH 008/110] add rth home offset option --- src/main/fc/settings.yaml | 9 +++++++-- src/main/navigation/navigation.c | 25 ++++++++++++++++++------- src/main/navigation/navigation.h | 4 +++- 3 files changed, 28 insertions(+), 10 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 835f1331782..aff03e1e442 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -80,7 +80,7 @@ tables: - name: debug_modes values: ["NONE", "GYRO", "NOTCH", "NAV_LANDING", "FW_ALTITUDE", "AGL", "FLOW_RAW", "FLOW", "SBUS", "FPORT", "ALWAYS", "STAGE2", "SAG_COMP_VOLTAGE", - "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "GENERIC", "ITERM_RELAX", + "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "GENERIC", "ITERM_RELAX", "D_BOOST", "ANTIGRAVITY", "FFT", "FFT_TIME", "FFT_FREQ", "ERPM"] - name: async_mode values: ["NONE", "GYRO", "ALL"] @@ -1442,7 +1442,12 @@ groups: - name: nav_rth_home_altitude field: general.rth_home_altitude max: 65000 - + - name: nav_rth_home_offset_distance + field: general.rth_home_offset_distance + max: 650 + - name: nav_rth_home_offset_direction + field: general.rth_home_offset_direction + max: 359 - name: nav_mc_bank_angle field: mc.max_bank_angle min: 15 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index d20073bcf6c..a54f66f65c9 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -56,7 +56,6 @@ #include "sensors/acceleration.h" #include "sensors/boardalignment.h" - // Multirotors: #define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt) #define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend) @@ -80,7 +79,7 @@ radar_pois_t radar_pois[RADAR_MAX_POIS]; PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0); #endif -PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 4); +PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 5); PG_RESET_TEMPLATE(navConfig_t, navConfig, .general = { @@ -115,7 +114,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .rth_home_altitude = 0, // altitude in centimeters .rth_abort_threshold = 50000, // centimeters - 500m should be safe for all aircraft .max_terrain_follow_altitude = 100, // max altitude in centimeters in terrain following mode - }, + .rth_home_offset_distance = 0, // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) + .rth_home_offset_direction = 0, // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) + }, // MC-specific .mc = { @@ -129,7 +130,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .braking_boost_timeout = 750, // Timout boost after 750ms .braking_boost_speed_threshold = 150, // Boost can happen only above 1.5m/s .braking_boost_disengage_speed = 100, // Disable boost at 1m/s - .braking_bank_angle = 40, // Max braking angle + .braking_bank_angle = 40, // Max braking angle .posDecelerationTime = 120, // posDecelerationTime * 100 .posResponseExpo = 10, // posResponseExpo * 100 }, @@ -2220,6 +2221,7 @@ static navigationHomeFlags_t navigationActualStateHomeValidity(void) /*----------------------------------------------------------- * Update home position, calculate distance and bearing to home *-----------------------------------------------------------*/ + void updateHomePosition(void) { // Disarmed and have a valid position, constantly update home @@ -2238,7 +2240,15 @@ void updateHomePosition(void) break; } if (setHome) { - setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); + if (navConfig()->general.rth_home_offset_distance != 0) { // apply user defined offset + fpVector3_t newHome; + newHome.x = posControl.actualState.abs.pos.x + 100 * navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + newHome.y = posControl.actualState.abs.pos.y + 100 * navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + newHome.z = posControl.actualState.abs.pos.z; + setHomePosition(&newHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); + } else { + setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); + } } } } @@ -2556,6 +2566,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) // WP #0 - special waypoint - HOME if ((wpNumber == 0) && ARMING_FLAG(ARMED) && (posControl.flags.estPosStatus >= EST_USABLE) && posControl.gpsOrigin.valid && posControl.flags.isGCSAssistedNavigationEnabled) { // Forcibly set home position. Note that this is only valid if already armed, otherwise home will be reset instantly + geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, GEO_ALT_RELATIVE); setHomePosition(&wpPos.pos, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, NAV_HOME_VALID_ALL); } @@ -3134,7 +3145,7 @@ void navigationUsePIDs(void) // Initialize position hold P-controller for (int axis = 0; axis < 2; axis++) { navPidInit( - &posControl.pids.pos[axis], + &posControl.pids.pos[axis], (float)pidProfile()->bank_mc.pid[PID_POS_XY].P / 100.0f, 0.0f, 0.0f, @@ -3152,7 +3163,7 @@ void navigationUsePIDs(void) // Initialize altitude hold PID-controllers (pos_z, vel_z, acc_z navPidInit( - &posControl.pids.pos[Z], + &posControl.pids.pos[Z], (float)pidProfile()->bank_mc.pid[PID_POS_Z].P / 100.0f, 0.0f, 0.0f, diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index d8e81ca16d1..ccbf5b293f2 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -32,7 +32,7 @@ /* GPS Home location data */ extern gpsLocation_t GPS_home; -extern uint32_t GPS_distanceToHome; // distance to home point in meters +extern uint32_t GPS_distanceToHome; // distance to home point in meters extern int16_t GPS_directionToHome; // direction to home point in degrees extern bool autoThrottleManuallyIncreased; @@ -171,6 +171,8 @@ typedef struct navConfig_s { uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode + uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) + uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) } general; struct { From 41b2d112b810403b8145d818080b06ef23208252 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 19 Nov 2019 19:25:14 +0000 Subject: [PATCH 009/110] add Cli.md description for rth home offsets --- docs/Cli.md | 4 +++- src/main/fc/settings.yaml | 1 + src/main/navigation/navigation.c | 3 +-- src/main/navigation/navigation.h | 4 ++-- 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 11c7fd08fca..2e7f81f26ec 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -200,6 +200,8 @@ A shorter form is also supported to enable and disable functions using `serial < | nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | | nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | | nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) | +| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | | nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | | nav_mc_auto_disarm_delay | 2000 | | @@ -421,7 +423,7 @@ A shorter form is also supported to enable and disable functions using `serial < | dyn_notch_width_percent | 8 | Distance in % of the attenuated frequency for double dynamic filter notched. When set to `0` single dynamic notch filter is used | | dyn_notch_range | MEDIUM | Dynamic gyro filter range. Possible values `LOW` `MEDIUM` `HIGH`. `MEDIUM` should work best for 5-6" multirotors. `LOW` should work best with 7" and bigger. `HIGH` should work with everything below 4" | | dyn_notch_q | 120 | Q factor for dynamic notches | -| dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | +| dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | | gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz). Currently experimental | | pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch/Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | yaw_p_limit | 300 | | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index aff03e1e442..d173808bc6a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1448,6 +1448,7 @@ groups: - name: nav_rth_home_offset_direction field: general.rth_home_offset_direction max: 359 + - name: nav_mc_bank_angle field: mc.max_bank_angle min: 15 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index a54f66f65c9..7d6e1649930 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -56,6 +56,7 @@ #include "sensors/acceleration.h" #include "sensors/boardalignment.h" + // Multirotors: #define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt) #define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend) @@ -2221,7 +2222,6 @@ static navigationHomeFlags_t navigationActualStateHomeValidity(void) /*----------------------------------------------------------- * Update home position, calculate distance and bearing to home *-----------------------------------------------------------*/ - void updateHomePosition(void) { // Disarmed and have a valid position, constantly update home @@ -2566,7 +2566,6 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) // WP #0 - special waypoint - HOME if ((wpNumber == 0) && ARMING_FLAG(ARMED) && (posControl.flags.estPosStatus >= EST_USABLE) && posControl.gpsOrigin.valid && posControl.flags.isGCSAssistedNavigationEnabled) { // Forcibly set home position. Note that this is only valid if already armed, otherwise home will be reset instantly - geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, GEO_ALT_RELATIVE); setHomePosition(&wpPos.pos, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, NAV_HOME_VALID_ALL); } diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index ccbf5b293f2..6559fc2bac0 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -171,8 +171,8 @@ typedef struct navConfig_s { uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode - uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) - uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) + uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) + uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) } general; struct { From 7f5288ed0a84cfdbb5c7e35fd3bf61f3f126946a Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 21 Nov 2019 20:56:22 +0000 Subject: [PATCH 010/110] offsetHome --- src/main/navigation/navigation.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 7d6e1649930..cb508390bca 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2241,11 +2241,11 @@ void updateHomePosition(void) } if (setHome) { if (navConfig()->general.rth_home_offset_distance != 0) { // apply user defined offset - fpVector3_t newHome; - newHome.x = posControl.actualState.abs.pos.x + 100 * navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); - newHome.y = posControl.actualState.abs.pos.y + 100 * navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); - newHome.z = posControl.actualState.abs.pos.z; - setHomePosition(&newHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); + fpVector3_t offsetHome; + offsetHome.x = posControl.actualState.abs.pos.x + 100 * navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + offsetHome.y = posControl.actualState.abs.pos.y + 100 * navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + offsetHome.z = posControl.actualState.abs.pos.z; + setHomePosition(&offsetHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); } else { setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); } From 82def44e654eb8c43df77014aead3431debedcad Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 27 Nov 2019 10:40:10 +0100 Subject: [PATCH 011/110] Align servo MIN/MAX values with the one in configurator --- src/main/fc/cli.c | 4 ++-- src/main/flight/servos.h | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index a20f4c9c05b..95641b27f83 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1612,8 +1612,8 @@ static void cliServo(char *cmdline) servo = servoParamsMutable(i); if ( - arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX || - arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX || + arguments[MIN] < SERVO_OUTPUT_MIN || arguments[MIN] > SERVO_OUTPUT_MAX || + arguments[MAX] < SERVO_OUTPUT_MIN || arguments[MAX] > SERVO_OUTPUT_MAX || arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] || arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] || arguments[RATE] < -125 || arguments[RATE] > 125 diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 7d8a2d3ca15..f247f3ade37 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -108,9 +108,8 @@ typedef struct servoMixer_s { #define MAX_SERVO_RULES (2 * MAX_SUPPORTED_SERVOS) #define MAX_SERVO_SPEED UINT8_MAX -#define MAX_SERVO_BOXES 3 - -#define SERVO_MIXER_INPUT_WIDTH 1000 +#define SERVO_OUTPUT_MAX 2500 +#define SERVO_OUTPUT_MIN 500 PG_DECLARE_ARRAY(servoMixer_t, MAX_SERVO_RULES, customServoMixers); From 15a536e2f25c5301de2603987144a9843570e288 Mon Sep 17 00:00:00 2001 From: hali9 Date: Wed, 27 Nov 2019 22:58:09 +0100 Subject: [PATCH 012/110] WP linear climb dive --- src/main/navigation/navigation.c | 18 +++++++++++++----- src/main/navigation/navigation_private.h | 3 +++ 2 files changed, 16 insertions(+), 5 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index d20073bcf6c..d681c93bdc8 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1368,6 +1368,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav switch (posControl.waypointList[posControl.activeWaypointIndex].action) { case NAV_WP_ACTION_WAYPOINT: calculateAndSetActiveWaypoint(&posControl.waypointList[posControl.activeWaypointIndex]); + posControl.wpInitialDistance = calculateDistanceToDestination(&posControl.activeWaypoint.pos); + posControl.wpInitialAltitude = posControl.actualState.abs.pos.z; return NAV_FSM_EVENT_SUCCESS; // will switch to NAV_STATE_WAYPOINT_IN_PROGRESS case NAV_WP_ACTION_RTH: @@ -1392,7 +1394,13 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na return NAV_FSM_EVENT_SUCCESS; // will switch to NAV_STATE_WAYPOINT_REACHED } else { - setDesiredPosition(&posControl.activeWaypoint.pos, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_BEARING); + fpVector3_t tmpWaypoint; + tmpWaypoint.x = posControl.activeWaypoint.pos.x; + tmpWaypoint.y = posControl.activeWaypoint.pos.y; + tmpWaypoint.z = scaleRange(constrainf(posControl.wpDistance, posControl.wpInitialDistance / 10, posControl.wpInitialDistance), + posControl.wpInitialDistance, posControl.wpInitialDistance / 10, + posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z); + setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING); return NAV_FSM_EVENT_NONE; // will re-process state in >10ms } break; @@ -2040,15 +2048,15 @@ bool isWaypointMissed(const navWaypointPosition_t * waypoint) static bool isWaypointPositionReached(const fpVector3_t * pos, const bool isWaypointHome) { // We consider waypoint reached if within specified radius - const uint32_t wpDistance = calculateDistanceToDestination(pos); + posControl.wpDistance = calculateDistanceToDestination(pos); if (STATE(FIXED_WING) && isWaypointHome) { // Airplane will do a circular loiter over home and might never approach it closer than waypoint_radius - need extra check - return (wpDistance <= navConfig()->general.waypoint_radius) - || (wpDistance <= (navConfig()->fw.loiter_radius * 1.10f)); // 10% margin of desired circular loiter radius + return (posControl.wpDistance <= navConfig()->general.waypoint_radius) + || (posControl.wpDistance <= (navConfig()->fw.loiter_radius * 1.10f)); // 10% margin of desired circular loiter radius } else { - return (wpDistance <= navConfig()->general.waypoint_radius); + return (posControl.wpDistance <= navConfig()->general.waypoint_radius); } } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 14eaa21a3ab..a11e9a0f62c 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -354,6 +354,9 @@ typedef struct { navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; + float wpInitialAltitude; // Altitude at start of WP + float wpInitialDistance; // Distance when starting flight to WP + float wpDistance; // Distance to active WP /* Internals & statistics */ int16_t rcAdjustment[4]; From 0da1746f8158374b24c74647f134725f6b9b5d36 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Fri, 29 Nov 2019 08:48:30 +0100 Subject: [PATCH 013/110] [TARGET] Mamba F722S (with fixes by namirda) rebased --- src/main/target/MAMBAF722/config.c | 52 ++++++++ src/main/target/MAMBAF722/target.c | 38 ++++++ src/main/target/MAMBAF722/target.h | 176 ++++++++++++++++++++++++++++ src/main/target/MAMBAF722/target.mk | 14 +++ 4 files changed, 280 insertions(+) create mode 100644 src/main/target/MAMBAF722/config.c create mode 100644 src/main/target/MAMBAF722/target.c create mode 100644 src/main/target/MAMBAF722/target.h create mode 100644 src/main/target/MAMBAF722/target.mk diff --git a/src/main/target/MAMBAF722/config.c b/src/main/target/MAMBAF722/config.c new file mode 100644 index 00000000000..4d92eb37ae6 --- /dev/null +++ b/src/main/target/MAMBAF722/config.c @@ -0,0 +1,52 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include + +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" + +void targetConfiguration(void) +{ + // RX6 is hard-wired to ESC-telemetry + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_ESCSERIAL; +} diff --git a/src/main/target/MAMBAF722/target.c b/src/main/target/MAMBAF722/target.c new file mode 100644 index 00000000000..09a4818256e --- /dev/null +++ b/src/main/target/MAMBAF722/target.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#include + +#include "platform.h" +#include "drivers/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – UP2-1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – UP2-1 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 0 ), // S3_OUT – UP2-5 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – UP2-5 + + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – DMA1_ST6 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h new file mode 100644 index 00000000000..63989ba97ce --- /dev/null +++ b/src/main/target/MAMBAF722/target.h @@ -0,0 +1,176 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "MBF7" +#define USBD_PRODUCT_STRING "MAMBAF722" + +// ******** Board LEDs ********************** +#define LED0 PC15 +#define LED1 PC14 + +// ******* Beeper *********** +#define BEEPER PB2 +#define BEEPER_INVERTED + + +// ******* GYRO and ACC ******** +#define USE_EXTI +#define USE_GYRO_EXTI +#define GYRO_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_GYRO +#define USE_GYRO_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG + +#define USE_ACC +#define USE_ACC_MPU6000 +#define ACC_MPU6500_ALIGN CW180_DEG + +// *************** Baro ************************** +#define USE_I2C +#define USE_I2C_DEVICE_2 + +#define I2C2_SCL PB10 // SCL pad TX3 +#define I2C2_SDA PB11 // SDA pad RX3 +#define DEFAULT_I2C_BUS BUS_I2C2 + +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL + +// ******* SERIAL ******** +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_SOFTSERIAL1 + +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 + +// ******* SPI ******** +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define RSSI_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 + +#define VBAT_SCALE_DEFAULT 1100 + +// ******* OSD ******** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +//******* FLASH ******** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB3 + +// ******* FEATURES ******** +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART2 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define TARGET_MOTOR_COUNT 4 + +// ESC-related features +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/MAMBAF722/target.mk b/src/main/target/MAMBAF722/target.mk new file mode 100644 index 00000000000..1902b593105 --- /dev/null +++ b/src/main/target/MAMBAF722/target.mk @@ -0,0 +1,14 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c From 5b11bdca51348b99b43b98a47379edab0d43125b Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Fri, 29 Nov 2019 20:22:27 +0100 Subject: [PATCH 014/110] [TARGET] Add built-in bluetooth on UART4 to MAMBA F722S --- src/main/target/MAMBAF722/config.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/target/MAMBAF722/config.c b/src/main/target/MAMBAF722/config.c index 4d92eb37ae6..97de32d85ae 100644 --- a/src/main/target/MAMBAF722/config.c +++ b/src/main/target/MAMBAF722/config.c @@ -49,4 +49,8 @@ void targetConfiguration(void) { // RX6 is hard-wired to ESC-telemetry serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_ESCSERIAL; + + // Built-in bluetooth on SERIAL4 + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_19200; } From ca46d7ab286eafcb3f49248bc9acd6ac5dd6ecfb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Fri, 29 Nov 2019 20:22:27 +0100 Subject: [PATCH 015/110] PID/PIFF refactoring (#5129) * Stage 1 PID/PIFF refactoring * Fix F3 compilation * Minor speedup * Make PID controller type configurable * fix compilation * Further minor optimizations * Fix mixer integration * Move some mixer routines to FASTRAM and precompute constants * Run applyMotorRateLimiting only when needed * Revert "Move some mixer routines to FASTRAM and precompute constants" This reverts commit 31370c12887ac0d24d2d92c190aab9f09c1cf8a5. * Revert "Minor speedup" This reverts commit 02b58e5f05fdeaf47511d00a2424a0dbd87230df. * fix compilation * Remove unused parameter * Fix F3 --- src/main/common/maths.c | 3 +- src/main/fc/settings.yaml | 6 + src/main/flight/mixer.c | 92 +++++++------ src/main/flight/pid.c | 219 +++++++++++++++++++------------ src/main/flight/pid.h | 10 +- src/main/target/OMNIBUS/target.h | 2 + 6 files changed, 204 insertions(+), 128 deletions(-) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 71d3d741424..13d615e361a 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -23,6 +23,7 @@ #include "maths.h" #include "vector.h" #include "quaternion.h" +#include "platform.h" // http://lolengine.net/blog/2011/12/21/better-function-approximations // Chebyshev http://stackoverflow.com/questions/345085/how-do-trigonometric-functions-work/345117#345117 @@ -158,7 +159,7 @@ int constrain(int amt, int low, int high) return amt; } -float constrainf(float amt, float low, float high) +float FAST_CODE NOINLINE constrainf(float amt, float low, float high) { if (amt < low) return low; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2b6cf11bbc3..8c583229c8d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -135,6 +135,9 @@ tables: - name: dynamicFilterRangeTable values: ["HIGH", "MEDIUM", "LOW"] enum: dynamicFilterRange_e + - name: pidTypeTable + values: ["NONE", "PID", "PIFF", "AUTO"] + enum: pidType_e groups: - name: PG_GYRO_CONFIG @@ -1225,6 +1228,9 @@ groups: condition: USE_ANTIGRAVITY min: 1 max: 30 + - name: pid_type + field: pidControllerType + table: pidTypeTable - name: PG_PID_AUTOTUNE_CONFIG type: pidAutotuneConfig_t diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 0592866f6cb..60c8e03f069 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -110,6 +110,9 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); +typedef void (*motorRateLimitingApplyFnPtr)(const float dT); +static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn; + static void computeMotorCount(void) { motorCount = 0; @@ -154,6 +157,49 @@ void mixerUpdateStateFlags(void) } } +void nullMotorRateLimiting(const float dT) +{ + UNUSED(dT); +} + +void applyMotorRateLimiting(const float dT) +{ + static float motorPrevious[MAX_SUPPORTED_MOTORS] = { 0 }; + + if (feature(FEATURE_3D)) { + // FIXME: Don't apply rate limiting in 3D mode + for (int i = 0; i < motorCount; i++) { + motorPrevious[i] = motor[i]; + } + } + else { + // Calculate max motor step + const uint16_t motorRange = motorConfig()->maxthrottle - motorConfig()->minthrottle; + const float motorMaxInc = (motorConfig()->motorAccelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorAccelTimeMs * 1e-3f); + const float motorMaxDec = (motorConfig()->motorDecelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorDecelTimeMs * 1e-3f); + + for (int i = 0; i < motorCount; i++) { + // Apply motor rate limiting + motorPrevious[i] = constrainf(motor[i], motorPrevious[i] - motorMaxDec, motorPrevious[i] + motorMaxInc); + + // Handle throttle below min_throttle (motor start/stop) + if (motorPrevious[i] < motorConfig()->minthrottle) { + if (motor[i] < motorConfig()->minthrottle) { + motorPrevious[i] = motor[i]; + } + else { + motorPrevious[i] = motorConfig()->minthrottle; + } + } + } + } + + // Update motor values + for (int i = 0; i < motorCount; i++) { + motor[i] = motorPrevious[i]; + } +} + void mixerInit(void) { computeMotorCount(); @@ -164,6 +210,12 @@ void mixerInit(void) } mixerResetDisarmedMotors(); + + if (motorConfig()->motorAccelTimeMs || motorConfig()->motorDecelTimeMs) { + motorRateLimitingApplyFn = applyMotorRateLimiting; + } else { + motorRateLimitingApplyFn = nullMotorRateLimiting; + } } void mixerResetDisarmedMotors(void) @@ -240,44 +292,6 @@ void stopPwmAllMotors(void) pwmShutdownPulsesForAllMotors(motorCount); } -static void applyMotorRateLimiting(const float dT) -{ - static float motorPrevious[MAX_SUPPORTED_MOTORS] = { 0 }; - - if (feature(FEATURE_3D)) { - // FIXME: Don't apply rate limiting in 3D mode - for (int i = 0; i < motorCount; i++) { - motorPrevious[i] = motor[i]; - } - } - else { - // Calculate max motor step - const uint16_t motorRange = motorConfig()->maxthrottle - motorConfig()->minthrottle; - const float motorMaxInc = (motorConfig()->motorAccelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorAccelTimeMs * 1e-3f); - const float motorMaxDec = (motorConfig()->motorDecelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorDecelTimeMs * 1e-3f); - - for (int i = 0; i < motorCount; i++) { - // Apply motor rate limiting - motorPrevious[i] = constrainf(motor[i], motorPrevious[i] - motorMaxDec, motorPrevious[i] + motorMaxInc); - - // Handle throttle below min_throttle (motor start/stop) - if (motorPrevious[i] < motorConfig()->minthrottle) { - if (motor[i] < motorConfig()->minthrottle) { - motorPrevious[i] = motor[i]; - } - else { - motorPrevious[i] = motorConfig()->minthrottle; - } - } - } - } - - // Update motor values - for (int i = 0; i < motorCount; i++) { - motor[i] = motorPrevious[i]; - } -} - void FAST_CODE NOINLINE mixTable(const float dT) { int16_t input[3]; // RPY, range [-500:+500] @@ -414,7 +428,7 @@ void FAST_CODE NOINLINE mixTable(const float dT) } /* Apply motor acceleration/deceleration limit */ - applyMotorRateLimiting(dT); + motorRateLimitingApplyFn(dT); } motorStatus_e getMotorStatus(void) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 377bae1d281..f0b943d2985 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -91,14 +91,15 @@ typedef struct { pt1Filter_t dBoostLpf; biquadFilter_t dBoostGyroLpf; #endif + bool itermLimitActive; } pidState_t; STATIC_FASTRAM filterApplyFnPtr notchFilterApplyFn; STATIC_FASTRAM bool pidFiltersConfigured = false; -FASTRAM float headingHoldCosZLimit; -FASTRAM int16_t headingHoldTarget; -STATIC_FASTRAM pt1Filter_t headingHoldRateFilter; -STATIC_FASTRAM pt1Filter_t fixedWingTpaFilter; +static EXTENDED_FASTRAM float headingHoldCosZLimit; +static EXTENDED_FASTRAM int16_t headingHoldTarget; +static EXTENDED_FASTRAM pt1Filter_t headingHoldRateFilter; +static EXTENDED_FASTRAM pt1Filter_t fixedWingTpaFilter; // Thrust PID Attenuation factor. 0.0f means fully attenuated, 1.0f no attenuation is applied STATIC_FASTRAM bool pidGainsUpdateRequired; @@ -132,8 +133,19 @@ static EXTENDED_FASTRAM float dBoostMaxAtAlleceleration; static EXTENDED_FASTRAM uint16_t yawPLimit; static EXTENDED_FASTRAM uint8_t yawLpfHz; +static EXTENDED_FASTRAM uint16_t pidSumLimit; +static EXTENDED_FASTRAM float motorItermWindupPoint; +static EXTENDED_FASTRAM float antiWindupScaler; +#ifdef USE_ANTIGRAVITY +static EXTENDED_FASTRAM float iTermAntigravityGain; +#endif +static EXTENDED_FASTRAM uint8_t usedPidControllerType; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 10); +typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t axis, float dT); +static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; +static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; + +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 11); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -238,40 +250,9 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .antigravityGain = 1.0f, .antigravityAccelerator = 1.0f, .antigravityCutoff = ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF, + .pidControllerType = PID_TYPE_AUTO, ); -void pidInit(void) -{ - pidResetTPAFilter(); - - // Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold - headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) * - cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_PITCH])); - - pidGainsUpdateRequired = false; - - itermRelax = pidProfile()->iterm_relax; - itermRelaxType = pidProfile()->iterm_relax_type; - itermRelaxSetpointThreshold = MC_ITERM_RELAX_SETPOINT_THRESHOLD * MC_ITERM_RELAX_CUTOFF_DEFAULT / pidProfile()->iterm_relax_cutoff; - - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) { - yawPLimit = pidProfile()->yaw_p_limit; - } else { - yawPLimit = 0; - } - yawLpfHz = pidProfile()->yaw_lpf_hz; - -#ifdef USE_D_BOOST - dBoostFactor = pidProfile()->dBoostFactor; - dBoostMaxAtAlleceleration = pidProfile()->dBoostMaxAtAlleceleration; -#endif - -#ifdef USE_ANTIGRAVITY - antigravityGain = pidProfile()->antigravityGain; - antigravityAccelerator = pidProfile()->antigravityAccelerator; -#endif -} - bool pidInitFilters(void) { const uint32_t refreshRate = getLooptime(); @@ -338,7 +319,7 @@ bool pidInitFilters(void) void pidResetTPAFilter(void) { - if (STATE(FIXED_WING) && currentControlRateProfile->throttle.fixedWingTauMs > 0) { + if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) { pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, getLooptime() * 1e-6f); pt1FilterReset(&fixedWingTpaFilter, motorConfig()->minthrottle); } @@ -436,7 +417,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT) STATIC_FASTRAM uint16_t prevThrottle = 0; // Check if throttle changed. Different logic for fixed wing vs multirotor - if (STATE(FIXED_WING) && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { + if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { uint16_t filteredThrottle = pt1FilterApply3(&fixedWingTpaFilter, rcCommand[THROTTLE], dT); if (filteredThrottle != prevThrottle) { prevThrottle = filteredThrottle; @@ -451,7 +432,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT) } #ifdef USE_ANTIGRAVITY - if (!STATE(FIXED_WING)) { + if (usedPidControllerType == PID_TYPE_PID) { antigravityThrottleHpf = rcCommand[THROTTLE] - pt1FilterApply(&antigravityThrottleLpf, rcCommand[THROTTLE]); } #endif @@ -468,12 +449,12 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT) return; } - const float tpaFactor = STATE(FIXED_WING) ? calculateFixedWingTPAFactor(prevThrottle) : calculateMultirotorTPAFactor(); + const float tpaFactor = usedPidControllerType == PID_TYPE_PIFF ? calculateFixedWingTPAFactor(prevThrottle) : calculateMultirotorTPAFactor(); // PID coefficients can be update only with THROTTLE and TPA or inflight PID adjustments //TODO: Next step would be to update those only at THROTTLE or inflight adjustments change for (int axis = 0; axis < 3; axis++) { - if (STATE(FIXED_WING)) { + if (usedPidControllerType == PID_TYPE_PIFF) { // Airplanes - scale all PIDs according to TPA pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * tpaFactor; pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * tpaFactor; @@ -598,6 +579,20 @@ static FAST_CODE NOINLINE float pTermProcess(pidState_t *pidState, flight_dynami return newPTerm; } +static void applyItermLimiting(pidState_t *pidState) { + if (pidState->itermLimitActive) { + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); + } else { + pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); + } +} + +static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { + UNUSED(pidState); + UNUSED(axis); + UNUSED(dT); +} + static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { const float rateError = pidState->rateTarget - pidState->gyroRate; @@ -607,11 +602,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh // Calculate integral pidState->errorGyroIf += rateError * pidState->kI * dT; - if (STATE(ANTI_WINDUP) || isFixedWingItermLimitActive(pidState->stickPosition)) { - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); - } else { - pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); - } + applyItermLimiting(pidState); if (pidProfile()->fixedWingItermThrowLimit != 0) { pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit); @@ -623,7 +614,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh } #endif - axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidProfile()->pidSumLimit, +pidProfile()->pidSumLimit); + axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidSumLimit, +pidSumLimit); #ifdef USE_BLACKBOX axisPID_P[axis] = newPTerm; @@ -660,7 +651,7 @@ static void FAST_CODE applyItermRelax(const int axis, const float gyroRate, floa } } #ifdef USE_D_BOOST -static float FAST_CODE applyDBoost(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { +static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) { float dBoost = 1.0f; @@ -681,22 +672,21 @@ static float FAST_CODE applyDBoost(pidState_t *pidState, flight_dynamics_index_t return dBoost; } #else -static float applyDBoost(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { +static float applyDBoost(pidState_t *pidState, float dT) { UNUSED(pidState); - UNUSED(axis); UNUSED(dT); return 1.0f; } #endif -static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) +static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { const float rateError = pidState->rateTarget - pidState->gyroRate; const float newPTerm = pTermProcess(pidState, axis, rateError, dT); // Calculate new D-term float newDTerm; - if (pidBank()->pid[axis].D == 0) { + if (pidState->kD == 0) { // optimisation for when D8 is zero, often used by YAW axis newDTerm = 0; } else { @@ -707,15 +697,13 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered); // Apply additional lowpass - if (pidProfile()->dterm_lpf_hz) { - deltaFiltered = biquadFilterApply(&pidState->deltaLpfState, deltaFiltered); - } + deltaFiltered = dTermLpfFilterApplyFn(&pidState->deltaLpfState, deltaFiltered); firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered); newDTerm = firFilterApply(&pidState->gyroRateFilter); // Calculate derivative - newDTerm = newDTerm * (pidState->kD / dT) * applyDBoost(pidState, axis, dT); + newDTerm = newDTerm * (pidState->kD / dT) * applyDBoost(pidState, dT); // Additionally constrain D newDTerm = constrainf(newDTerm, -300.0f, 300.0f); @@ -723,17 +711,12 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl // TODO: Get feedback from mixer on available correction range for each axis const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf; - const float newOutputLimited = constrainf(newOutput, -pidProfile()->pidSumLimit, +pidProfile()->pidSumLimit); - - // Prevent strong Iterm accumulation during stick inputs - const float motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); - const float antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); + const float newOutputLimited = constrainf(newOutput, -pidSumLimit, +pidSumLimit); float itermErrorRate = rateError; applyItermRelax(axis, pidState->gyroRate, pidState->rateTarget, &itermErrorRate); #ifdef USE_ANTIGRAVITY - const float iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); itermErrorRate *= iTermAntigravityGain; #endif @@ -741,11 +724,7 @@ static void FAST_CODE pidApplyMulticopterRateController(pidState_t *pidState, fl + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); // Don't grow I-term if motors are at their limit - if (STATE(ANTI_WINDUP) || mixerIsOutputSaturated()) { - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); - } else { - pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); - } + applyItermLimiting(pidState); axisPID[axis] = newOutputLimited; @@ -937,7 +916,20 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -void FAST_CODE pidController(float dT) +void FAST_CODE checkItermLimitingActive(pidState_t *pidState) +{ + bool shouldActivate; + if (usedPidControllerType == PID_TYPE_PIFF) { + shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); + } else + { + shouldActivate = mixerIsOutputSaturated(); + } + + pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; +} + +void FAST_CODE NOINLINE pidController(float dT) { if (!pidFiltersConfigured) { return; @@ -988,30 +980,29 @@ void FAST_CODE pidController(float dT) pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } - // Apply setpoint rate of change limits - for (int axis = 0; axis < 3; axis++) { - pidApplySetpointRateLimiting(&pidState[axis], axis, dT); - } + // Prevent strong Iterm accumulation during stick inputs + antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); + +#ifdef USE_ANTIGRAVITY + iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); +#endif - // Step 4: Run gyro-driven control for (int axis = 0; axis < 3; axis++) { - // Apply PID setpoint controller - if (STATE(FIXED_WING)) { - pidApplyFixedWingRateController(&pidState[axis], axis, dT); - } - else { - pidApplyMulticopterRateController(&pidState[axis], axis, dT); - } + // Apply setpoint rate of change limits + pidApplySetpointRateLimiting(&pidState[axis], axis, dT); + + // Step 4: Run gyro-driven control + checkItermLimitingActive(&pidState[axis]); + pidControllerApplyFn(&pidState[axis], axis, dT); } } pidType_e pidIndexGetType(pidIndex_e pidIndex) { + if (pidIndex == PID_ROLL || pidIndex == PID_PITCH || pidIndex == PID_YAW) { + return usedPidControllerType; + } if (STATE(FIXED_WING)) { - // FW specific - if (pidIndex == PID_ROLL || pidIndex == PID_PITCH || pidIndex == PID_YAW) { - return PID_TYPE_PIFF; - } if (pidIndex == PID_VEL_XY || pidIndex == PID_VEL_Z) { return PID_TYPE_NONE; } @@ -1022,3 +1013,61 @@ pidType_e pidIndexGetType(pidIndex_e pidIndex) } return PID_TYPE_PID; } + +void pidInit(void) +{ + pidResetTPAFilter(); + + // Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold + headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) * + cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_PITCH])); + + pidGainsUpdateRequired = false; + + itermRelax = pidProfile()->iterm_relax; + itermRelaxType = pidProfile()->iterm_relax_type; + itermRelaxSetpointThreshold = MC_ITERM_RELAX_SETPOINT_THRESHOLD * MC_ITERM_RELAX_CUTOFF_DEFAULT / pidProfile()->iterm_relax_cutoff; + + if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) { + yawPLimit = pidProfile()->yaw_p_limit; + } else { + yawPLimit = 0; + } + yawLpfHz = pidProfile()->yaw_lpf_hz; + pidSumLimit = pidProfile()->pidSumLimit; + motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); + +#ifdef USE_D_BOOST + dBoostFactor = pidProfile()->dBoostFactor; + dBoostMaxAtAlleceleration = pidProfile()->dBoostMaxAtAlleceleration; +#endif + +#ifdef USE_ANTIGRAVITY + antigravityGain = pidProfile()->antigravityGain; + antigravityAccelerator = pidProfile()->antigravityAccelerator; +#endif + + if (pidProfile()->pidControllerType == PID_TYPE_AUTO) { + if (STATE(FIXED_WING)) { + usedPidControllerType = PID_TYPE_PIFF; + } else { + usedPidControllerType = PID_TYPE_PID; + } + } else { + usedPidControllerType = pidProfile()->pidControllerType; + } + + if (pidProfile()->dterm_lpf_hz) { + dTermLpfFilterApplyFn = (filterApplyFnPtr) biquadFilterApply; + } else { + dTermLpfFilterApplyFn = nullFilterApply; + } + + if (usedPidControllerType == PID_TYPE_PIFF) { + pidControllerApplyFn = pidApplyFixedWingRateController; + } else if (usedPidControllerType == PID_TYPE_PID) { + pidControllerApplyFn = pidApplyMulticopterRateController; + } else { + pidControllerApplyFn = nullRateController; + } +} diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 312d19637b9..41f30dbf2d2 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -72,9 +72,10 @@ typedef enum { // TODO(agh): PIDFF typedef enum { - PID_TYPE_NONE, // Not used in the current platform/mixer/configuration + PID_TYPE_NONE = 0, // Not used in the current platform/mixer/configuration PID_TYPE_PID, // Uses P, I and D terms PID_TYPE_PIFF, // Uses P, I and FF, ignoring D + PID_TYPE_AUTO, // Autodetect } pidType_e; typedef struct pid8_s { @@ -100,6 +101,7 @@ typedef enum { } itermRelaxType_e; typedef struct pidProfile_s { + uint8_t pidControllerType; pidBank_t bank_fw; pidBank_t bank_mc; @@ -155,8 +157,10 @@ typedef struct pidAutotuneConfig_s { PG_DECLARE_PROFILE(pidProfile_t, pidProfile); PG_DECLARE(pidAutotuneConfig_t, pidAutotuneConfig); -static inline const pidBank_t * pidBank(void) { return STATE(FIXED_WING) ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } -static inline pidBank_t * pidBankMutable(void) { return STATE(FIXED_WING) ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } +static uint8_t usedPidControllerType; + +static inline const pidBank_t * pidBank(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } +static inline pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } extern int16_t axisPID[]; extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[]; diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 11270303791..f9fc0a6227d 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -154,3 +154,5 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) + +#undef USE_PWM_SERVO_DRIVER \ No newline at end of file From 99c22d39de33788400c6a54f9eb7e38379740153 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sat, 30 Nov 2019 11:16:28 +0100 Subject: [PATCH 016/110] [TARGET] Fix DSHOT on MAMBA F722S --- src/main/target/MAMBAF722/target.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/target/MAMBAF722/target.c b/src/main/target/MAMBAF722/target.c index 09a4818256e..14a8bf172f7 100644 --- a/src/main/target/MAMBAF722/target.c +++ b/src/main/target/MAMBAF722/target.c @@ -25,14 +25,14 @@ #include "drivers/bus.h" const timerHardware_t timerHardware[] = { - DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN + DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – UP2-1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – UP2-1 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 0 ), // S3_OUT – UP2-5 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – UP2-5 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – DMA1_ST6 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); From 5084477b37b87cceae614b6c5899788c7bf570b5 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sat, 30 Nov 2019 14:07:27 +0100 Subject: [PATCH 017/110] [TARGET] Fix MAMBAF405 device ID; Add MAMBAF405US target --- src/main/target/FURYF4OSD/target.h | 6 +- src/main/target/MAMBAF405US/config.c | 53 ++++++++ src/main/target/MAMBAF405US/target.c | 38 ++++++ src/main/target/MAMBAF405US/target.h | 188 ++++++++++++++++++++++++++ src/main/target/MAMBAF405US/target.mk | 13 ++ 5 files changed, 297 insertions(+), 1 deletion(-) create mode 100644 src/main/target/MAMBAF405US/config.c create mode 100644 src/main/target/MAMBAF405US/target.c create mode 100644 src/main/target/MAMBAF405US/target.h create mode 100644 src/main/target/MAMBAF405US/target.mk diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index 062d95b76e1..d380ac7bedd 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -17,9 +17,13 @@ #pragma once +#ifdef MAMBAF405 +#define TARGET_BOARD_IDENTIFIER "MBF4" +#define USBD_PRODUCT_STRING "MAMBAF405" +#else #define TARGET_BOARD_IDENTIFIER "FYF4" - #define USBD_PRODUCT_STRING "FuryF4" +#endif #define LED0 PB5 #define LED1 PB4 diff --git a/src/main/target/MAMBAF405US/config.c b/src/main/target/MAMBAF405US/config.c new file mode 100644 index 00000000000..636c30ed9b2 --- /dev/null +++ b/src/main/target/MAMBAF405US/config.c @@ -0,0 +1,53 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include + +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" + +void targetConfiguration(void) +{ + // MSP @ 19200 on SERIAL4 + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_19200; +} diff --git a/src/main/target/MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c new file mode 100644 index 00000000000..c79517e87f1 --- /dev/null +++ b/src/main/target/MAMBAF405US/target.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#include + +#include "platform.h" +#include "drivers/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7) + + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h new file mode 100644 index 00000000000..67b45f39e4f --- /dev/null +++ b/src/main/target/MAMBAF405US/target.h @@ -0,0 +1,188 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "MBUS" +#define USBD_PRODUCT_STRING "MAMBAF405US" + +// ******** Board LEDs ********************** +#define LED0 PC15 +#define LED1 PC14 + +// ******* Beeper *********** +#define BEEPER PC13 +#define BEEPER_INVERTED + + +// ******* GYRO and ACC ******** +#define USE_EXTI +#define USE_GYRO_EXTI +#define GYRO_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_GYRO +#define USE_GYRO_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG + +#define USE_ACC +#define USE_ACC_MPU6000 +#define ACC_MPU6500_ALIGN CW180_DEG + +// *************** Baro ************************** +#define USE_I2C +#define USE_I2C_DEVICE_2 + +#define I2C2_SCL PB10 // SCL pad TX3 +#define I2C2_SDA PB11 // SDA pad RX3 +#define DEFAULT_I2C_BUS BUS_I2C2 + +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL + +// ******* SERIAL ******** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +/* +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 +*/ + +#define SERIAL_PORT_COUNT 7 + +#define USE_UART_INVERTER +#define INVERTER_PIN_UART1_RX PC0 + + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PB0 + + +// ******* SPI ******** +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define RSSI_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 + +#define VBAT_SCALE_DEFAULT 1100 + +// ******* OSD ******** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +//******* FLASH ******** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB3 + +// ******* FEATURES ******** +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define TARGET_MOTOR_COUNT 4 + +// ESC-related features +#define USE_DSHOT +#define USE_SERIALSHOT +//#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/MAMBAF405US/target.mk b/src/main/target/MAMBAF405US/target.mk new file mode 100644 index 00000000000..43eadf6d0ca --- /dev/null +++ b/src/main/target/MAMBAF405US/target.mk @@ -0,0 +1,13 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c From a9f6f55a991fe0aab1bfe25cdda7514c0511e42e Mon Sep 17 00:00:00 2001 From: Konstantin Sharlaimov Date: Sat, 30 Nov 2019 18:47:04 +0100 Subject: [PATCH 018/110] Version bump to 2.4 --- src/main/build/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/build/version.h b/src/main/build/version.h index f509db3b54c..ec17abe33a6 100644 --- a/src/main/build/version.h +++ b/src/main/build/version.h @@ -16,7 +16,7 @@ */ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) -#define FC_VERSION_MINOR 3 // increment when a minor release is made (small new feature, change etc) +#define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc) #define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed #define STR_HELPER(x) #x From 5b57c7d728f0987def2f46ad6a503d5c15f1b6b5 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sun, 1 Dec 2019 00:33:46 +0100 Subject: [PATCH 019/110] Baro: add BMP388 driver --- src/main/drivers/barometer/barometer_bmp388.c | 348 ++++++++++++++++++ src/main/drivers/barometer/barometer_bmp388.h | 30 ++ src/main/drivers/bus.h | 1 + src/main/fc/settings.yaml | 2 +- src/main/sensors/barometer.c | 14 + src/main/sensors/barometer.h | 3 +- src/main/target/common_hardware.c | 11 + 7 files changed, 407 insertions(+), 2 deletions(-) create mode 100644 src/main/drivers/barometer/barometer_bmp388.c create mode 100644 src/main/drivers/barometer/barometer_bmp388.h diff --git a/src/main/drivers/barometer/barometer_bmp388.c b/src/main/drivers/barometer/barometer_bmp388.c new file mode 100644 index 00000000000..c35fbc05b4d --- /dev/null +++ b/src/main/drivers/barometer/barometer_bmp388.c @@ -0,0 +1,348 @@ +/* + * This file is part of iNav. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + * + * BMP388 Driver author: Dominic Clifton + * iNav port: Michel Pastor + */ + +#include +#include +#include + +#include +#include "build/build_config.h" +#include "build/debug.h" +#include "common/utils.h" +#include "common/log.h" // XXX + +#include "drivers/time.h" +#include "drivers/io.h" +#include "drivers/bus.h" +#include "drivers/barometer/barometer.h" +#include "drivers/barometer/barometer_bmp388.h" + +#if defined(USE_BARO) && (defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388)) + +#define BMP388_I2C_ADDR (0x76) // same as BMP280/BMP180 +#define BMP388_DEFAULT_CHIP_ID (0x50) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L130 + +#define BMP388_CMD_REG (0x7E) +#define BMP388_RESERVED_UPPER_REG (0x7D) +// everything between BMP388_RESERVED_UPPER_REG and BMP388_RESERVED_LOWER_REG is reserved. +#define BMP388_RESERVED_LOWER_REG (0x20) +#define BMP388_CONFIG_REG (0x1F) +#define BMP388_RESERVED_0x1E_REG (0x1E) +#define BMP388_ODR_REG (0x1D) +#define BMP388_OSR_REG (0x1C) +#define BMP388_PWR_CTRL_REG (0x1B) +#define BMP388_IF_CONFIG_REG (0x1A) +#define BMP388_INT_CTRL_REG (0x19) +#define BMP388_FIFO_CONFIG_2_REG (0x18) +#define BMP388_FIFO_CONFIG_1_REG (0x17) +#define BMP388_FIFO_WTM_1_REG (0x16) +#define BMP388_FIFO_WTM_0_REG (0x15) +#define BMP388_FIFO_DATA_REG (0x14) +#define BMP388_FIFO_LENGTH_1_REG (0x13) +#define BMP388_FIFO_LENGTH_0_REG (0x12) +#define BMP388_INT_STATUS_REG (0x11) +#define BMP388_EVENT_REG (0x10) +#define BMP388_SENSORTIME_3_REG (0x0F) // BME780 only +#define BMP388_SENSORTIME_2_REG (0x0E) +#define BMP388_SENSORTIME_1_REG (0x0D) +#define BMP388_SENSORTIME_0_REG (0x0C) +#define BMP388_RESERVED_0x0B_REG (0x0B) +#define BMP388_RESERVED_0x0A_REG (0x0A) + +// see friendly register names below +#define BMP388_DATA_5_REG (0x09) +#define BMP388_DATA_4_REG (0x08) +#define BMP388_DATA_3_REG (0x07) +#define BMP388_DATA_2_REG (0x06) +#define BMP388_DATA_1_REG (0x05) +#define BMP388_DATA_0_REG (0x04) + +#define BMP388_STATUS_REG (0x03) +#define BMP388_ERR_REG (0x02) +#define BMP388_RESERVED_0x01_REG (0x01) +#define BMP388_CHIP_ID_REG (0x00) + +// friendly register names, from datasheet 4.3.4 +#define BMP388_PRESS_MSB_23_16_REG BMP388_DATA_2_REG +#define BMP388_PRESS_LSB_15_8_REG BMP388_DATA_1_REG +#define BMP388_PRESS_XLSB_7_0_REG BMP388_DATA_0_REG + +// friendly register names, from datasheet 4.3.5 +#define BMP388_TEMP_MSB_23_16_REG BMP388_DATA_5_REG +#define BMP388_TEMP_LSB_15_8_REG BMP388_DATA_4_REG +#define BMP388_TEMP_XLSB_7_0_REG BMP388_DATA_3_REG + +#define BMP388_DATA_FRAME_SIZE ((BMP388_DATA_5_REG - BMP388_DATA_0_REG) + 1) // +1 for inclusive + +// from Datasheet 3.3 +#define BMP388_MODE_SLEEP (0x00) +#define BMP388_MODE_FORCED (0x01) +#define BMP388_MODE_NORMAL (0x02) + +#define BMP388_CALIRATION_LOWER_REG (0x30) // See datasheet 4.3.19, "calibration data" +#define BMP388_TRIMMING_NVM_PAR_T1_LSB_REG (0x31) // See datasheet 3.11.1 "Memory map trimming coefficients" +#define BMP388_TRIMMING_NVM_PAR_P11_REG (0x45) // See datasheet 3.11.1 "Memory map trimming coefficients" +#define BMP388_CALIRATION_UPPER_REG (0x57) + +#define BMP388_TRIMMING_DATA_LENGTH ((BMP388_TRIMMING_NVM_PAR_P11_REG - BMP388_TRIMMING_NVM_PAR_T1_LSB_REG) + 1) // +1 for inclusive + +#define BMP388_OVERSAMP_1X (0x00) +#define BMP388_OVERSAMP_2X (0x01) +#define BMP388_OVERSAMP_4X (0x02) +#define BMP388_OVERSAMP_8X (0x03) +#define BMP388_OVERSAMP_16X (0x04) +#define BMP388_OVERSAMP_32X (0x05) + +// INT_CTRL register +#define BMP388_INT_OD_BIT 0 +#define BMP388_INT_LEVEL_BIT 1 +#define BMP388_INT_LATCH_BIT 2 +#define BMP388_INT_FWTM_EN_BIT 3 +#define BMP388_INT_FFULL_EN_BIT 4 +#define BMP388_INT_RESERVED_5_BIT 5 +#define BMP388_INT_DRDY_EN_BIT 6 +#define BMP388_INT_RESERVED_7_BIT 7 + +// OSR register +#define BMP388_OSR_P_BIT 0 // to 2 +#define BMP388_OSR4_T_BIT 3 // to 5 +#define BMP388_OSR_P_MASK (0x03) // -----111 +#define BMP388_OSR4_T_MASK (0x38) // --111--- + +// configure pressure and temperature oversampling, forced sampling mode +#define BMP388_PRESSURE_OSR (BMP388_OVERSAMP_8X) +#define BMP388_TEMPERATURE_OSR (BMP388_OVERSAMP_1X) + +// see Datasheet 3.11.1 Memory Map Trimming Coefficients +typedef struct bmp388_calib_param_s { + uint16_t T1; + uint16_t T2; + int8_t T3; + int16_t P1; + int16_t P2; + int8_t P3; + int8_t P4; + uint16_t P5; + uint16_t P6; + int8_t P7; + int8_t P8; + int16_t P9; + int8_t P10; + int8_t P11; +} __attribute__((packed)) bmp388_calib_param_t; + +STATIC_ASSERT(sizeof(bmp388_calib_param_t) == BMP388_TRIMMING_DATA_LENGTH, bmp388_calibration_structure_incorrectly_packed); + +static bmp388_calib_param_t bmp388_cal; +// uncompensated pressure and temperature +static uint32_t bmp388_up = 0; +static uint32_t bmp388_ut = 0; +static uint8_t sensor_data[BMP388_DATA_FRAME_SIZE+1]; + +static int64_t t_lin = 0; + +static bool bmp388StartUT(baroDev_t *baro); +static bool bmp388GetUT(baroDev_t *baro); +static bool bmp388StartUP(baroDev_t *baro); +static bool bmp388GetUP(baroDev_t *baro); + +static bool bmp388Calculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature); + +static bool bmp388BeginForcedMeasurement(busDevice_t *busdev) +{ + // enable pressure measurement, temperature measurement, set power mode and start sampling + uint8_t mode = BMP388_MODE_FORCED << 4 | 1 << 1 | 1 << 0; + return busWrite(busdev, BMP388_PWR_CTRL_REG, mode); +} + +static bool bmp388StartUT(baroDev_t *baro) +{ + UNUSED(baro); + // dummy + return true; +} + +static bool bmp388GetUT(baroDev_t *baro) +{ + UNUSED(baro); + // dummy + return true; +} + +static bool bmp388StartUP(baroDev_t *baro) +{ + // start measurement + return bmp388BeginForcedMeasurement(baro->busDev); +} + +static bool bmp388GetUP(baroDev_t *baro) +{ + busReadBuf(baro->busDev, BMP388_DATA_0_REG, sensor_data, BMP388_DATA_FRAME_SIZE + 1); + + bmp388_up = sensor_data[1] << 0 | sensor_data[2] << 8 | sensor_data[3] << 16; + bmp388_ut = sensor_data[4] << 0 | sensor_data[5] << 8 | sensor_data[6] << 16; + return true; +} + +// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC +static int64_t bmp388CompensateTemperature(uint32_t uncomp_temperature) +{ + uint64_t partial_data1; + uint64_t partial_data2; + uint64_t partial_data3; + int64_t partial_data4; + int64_t partial_data5; + int64_t partial_data6; + int64_t comp_temp; + + partial_data1 = uncomp_temperature - (256 * bmp388_cal.T1); + partial_data2 = bmp388_cal.T2 * partial_data1; + partial_data3 = partial_data1 * partial_data1; + partial_data4 = (int64_t)partial_data3 * bmp388_cal.T3; + partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4); + partial_data6 = partial_data5 / 4294967296; + /* Update t_lin, needed for pressure calculation */ + t_lin = partial_data6; + comp_temp = (int64_t)((partial_data6 * 25) / 16384); + + return comp_temp; +} + +static uint64_t bmp388CompensatePressure(uint32_t uncomp_pressure) +{ + int64_t partial_data1; + int64_t partial_data2; + int64_t partial_data3; + int64_t partial_data4; + int64_t partial_data5; + int64_t partial_data6; + int64_t offset; + int64_t sensitivity; + uint64_t comp_press; + + partial_data1 = t_lin * t_lin; + partial_data2 = partial_data1 / 64; + partial_data3 = (partial_data2 * t_lin) / 256; + partial_data4 = (bmp388_cal.P8 * partial_data3) / 32; + partial_data5 = (bmp388_cal.P7 * partial_data1) * 16; + partial_data6 = (bmp388_cal.P6 * t_lin) * 4194304; + offset = (bmp388_cal.P5 * 140737488355328) + partial_data4 + partial_data5 + partial_data6; + + partial_data2 = (bmp388_cal.P4 * partial_data3) / 32; + partial_data4 = (bmp388_cal.P3 * partial_data1) * 4; + partial_data5 = (bmp388_cal.P2 - 16384) * t_lin * 2097152; + sensitivity = ((bmp388_cal.P1 - 16384) * 70368744177664) + partial_data2 + partial_data4 + partial_data5; + + partial_data1 = (sensitivity / 16777216) * uncomp_pressure; + partial_data2 = bmp388_cal.P10 * t_lin; + partial_data3 = partial_data2 + (65536 * bmp388_cal.P9); + partial_data4 = (partial_data3 * uncomp_pressure) / 8192; + partial_data5 = (partial_data4 * uncomp_pressure) / 512; + partial_data6 = (int64_t)((uint64_t)uncomp_pressure * (uint64_t)uncomp_pressure); + partial_data2 = (bmp388_cal.P11 * partial_data6) / 65536; + partial_data3 = (partial_data2 * uncomp_pressure) / 128; + partial_data4 = (offset / 4) + partial_data1 + partial_data5 + partial_data3; + comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776); + + return comp_press; +} + +STATIC_UNIT_TESTED bool bmp388Calculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature) +{ + UNUSED(baro); + + // calculate + int64_t t; + int64_t p; + + t = bmp388CompensateTemperature(bmp388_ut); + p = bmp388CompensatePressure(bmp388_up); + + if (pressure) + *pressure = (int32_t)(p / 256); + if (temperature) + *temperature = t; + + return true; +} + +#define DETECTION_MAX_RETRY_COUNT 5 +static bool deviceDetect(busDevice_t * busDev) +{ + for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) { + uint8_t chipId[2]; + + delay(100); + + bool ack = busReadBuf(busDev, BMP388_CHIP_ID_REG, chipId, 2); + + if (ack && chipId[1] == BMP388_DEFAULT_CHIP_ID) { + return true; + } + }; + + return false; +} + +bool bmp388Detect(baroDev_t *baro) +{ + baro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_BMP388, 0, OWNER_BARO); + if (baro->busDev == NULL) { + return false; + } + + busSetSpeed(baro->busDev, BUS_SPEED_STANDARD); + + if (!deviceDetect(baro->busDev)) { + busDeviceDeInit(baro->busDev); + return false; + } + + uint8_t calibration_buf[sizeof(bmp388_calib_param_t) + 1]; + + // read calibration + busReadBuf(baro->busDev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, calibration_buf, sizeof(bmp388_calib_param_t) + 1); + memcpy(&bmp388_cal, calibration_buf + 1, sizeof(bmp388_calib_param_t)); + + // set oversampling + power mode (forced), and start sampling + busWrite(baro->busDev, BMP388_OSR_REG, + ((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) | + ((BMP388_TEMPERATURE_OSR << BMP388_OSR4_T_BIT) & BMP388_OSR4_T_MASK) + ); + + bmp388BeginForcedMeasurement(baro->busDev); + + baro->ut_delay = 0; + baro->get_ut = bmp388GetUT; + baro->start_ut = bmp388StartUT; + + baro->up_delay = 234 + (392 + ((1 << (BMP388_PRESSURE_OSR + 1)) * 2000)) + (313 + ((1 << (BMP388_TEMPERATURE_OSR + 1)) * 2000)); + baro->start_up = bmp388StartUP; + baro->get_up = bmp388GetUP; + + baro->calculate = bmp388Calculate; + + return true; +} + +#endif diff --git a/src/main/drivers/barometer/barometer_bmp388.h b/src/main/drivers/barometer/barometer_bmp388.h new file mode 100644 index 00000000000..56c3ad44609 --- /dev/null +++ b/src/main/drivers/barometer/barometer_bmp388.h @@ -0,0 +1,30 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + * + * BMP388 Driver author: Dominic Clifton + * + * References: + * BMP388 datasheet - https://ae-bst.resource.bosch.com/media/_tech/media/datasheets/BST-BMP388-DS001.pdf + * BMP3-Sensor-API - https://github.com/BoschSensortec/BMP3-Sensor-API + * BMP280 Cleanflight driver + */ + +#pragma once + +bool bmp388Detect(baroDev_t *baro); diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index bccf9c252a9..843404573f3 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -103,6 +103,7 @@ typedef enum { DEVHW_MS5607, DEVHW_LPS25H, DEVHW_SPL06, + DEVHW_BMP388, /* Compass chips */ DEVHW_HMC5883, diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 835f1331782..dfea5166ca6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -16,7 +16,7 @@ tables: values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"] enum: opticalFlowSensor_e - name: baro_hardware - values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"] + values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"] enum: baroSensor_e - name: pitot_hardware values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"] diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 2e186217857..f9e72f15a8a 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -33,6 +33,7 @@ #include "drivers/barometer/barometer.h" #include "drivers/barometer/barometer_bmp085.h" #include "drivers/barometer/barometer_bmp280.h" +#include "drivers/barometer/barometer_bmp388.h" #include "drivers/barometer/barometer_lps25h.h" #include "drivers/barometer/barometer_fake.h" #include "drivers/barometer/barometer_ms56xx.h" @@ -132,6 +133,19 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse) } FALLTHROUGH; + case BARO_BMP388: +#if defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388) + if (bmp388Detect(dev)) { + baroHardware = BARO_BMP388; + break; + } +#endif + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (baroHardwareToUse != BARO_AUTODETECT) { + break; + } + FALLTHROUGH; + case BARO_SPL06: #if defined(USE_BARO_SPL06) || defined(USE_BARO_SPI_SPL06) if (spl06Detect(dev)) { diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index 3a01a45b5f7..3e10700f0c7 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -30,7 +30,8 @@ typedef enum { BARO_MS5607 = 5, BARO_LPS25H = 6, BARO_SPL06 = 7, - BARO_FAKE = 8, + BARO_BMP388 = 8, + BARO_FAKE = 9, BARO_MAX = BARO_FAKE } baroSensor_e; diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 4d83885d887..89816dc456c 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -97,6 +97,17 @@ #endif #endif +#if defined(USE_BARO_BMP388) + #if defined(BMP388_SPI_BUS) + BUSDEV_REGISTER_SPI(busdev_bmp388, DEVHW_BMP388, BMP388_SPI_BUS, BMP388_CS_PIN, NONE, DEVFLAGS_NONE); + #elif defined(BMP388_I2C_BUS) || defined(BARO_I2C_BUS) + #if !defined(BMP388_I2C_BUS) + #define BMP388_I2C_BUS BARO_I2C_BUS + #endif + BUSDEV_REGISTER_I2C(busdev_bmp388, DEVHW_BMP388, BMP388_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE); + #endif +#endif + #if defined(USE_BARO_SPL06) #if defined(SPL06_SPI_BUS) BUSDEV_REGISTER_SPI(busdev_spl06, DEVHW_SPL06, SPL06_SPI_BUS, SPL06_CS_PIN, NONE, DEVFLAGS_NONE); From 92820650c0dbcede8ffad453cb67e14cee055257 Mon Sep 17 00:00:00 2001 From: tiriad <42714516+tiriad@users.noreply.github.com> Date: Sun, 1 Dec 2019 16:45:10 +0100 Subject: [PATCH 020/110] Led fix in omnibusf4pro_ledstripm5 and simplified the code for the other targets based on this target I have not taken into account the first line in past revisions where omnibusf4pro_ledstripm5 was defined as omnibusf4pro, seeing that this form is simpler than others I have applied it to the variants of omnibusf4v3. --- src/main/target/OMNIBUSF4/target.c | 6 +++--- src/main/target/OMNIBUSF4/target.h | 29 +++++++++++++++++------------ 2 files changed, 20 insertions(+), 15 deletions(-) diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index 97e591b617a..5ceb77043a0 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -24,7 +24,7 @@ #include "drivers/bus.h" const timerHardware_t timerHardware[] = { -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN #else @@ -42,7 +42,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT #elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) @@ -59,7 +59,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT #endif -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!defined(OMNIBUSF4PRO_LEDSTRIPM5) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4) #endif }; diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 101d2d98ea3..0825193bb82 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -17,12 +17,18 @@ #pragma once +//Same target as OMNIBUSF4PRO with LED strip in M5 #ifdef OMNIBUSF4PRO_LEDSTRIPM5 #define OMNIBUSF4PRO #endif +//Same target as OMNIBUSF4V3 with softserial in M5 and M6 +#if defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#define OMNIBUSF4V3 +#endif + #ifdef OMNIBUSF4PRO #define TARGET_BOARD_IDENTIFIER "OBSD" -#elif defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#elif defined(OMNIBUSF4V3) #define TARGET_BOARD_IDENTIFIER "OB43" #elif defined(DYSF4PRO) #define TARGET_BOARD_IDENTIFIER "DYS4" @@ -69,8 +75,7 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -// Long sentence, OMNIBUSF4 always defined -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define USE_GYRO_MPU6000 #define GYRO_MPU6000_ALIGN CW270_DEG @@ -85,7 +90,7 @@ #endif // Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define MPU6500_CS_PIN MPU6000_CS_PIN #define MPU6500_SPI_BUS MPU6000_SPI_BUS @@ -111,7 +116,7 @@ #define USE_BARO -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define USE_BARO_BMP280 #define BMP280_SPI_BUS BUS_SPI3 #define BMP280_CS_PIN PB3 // v1 @@ -141,7 +146,7 @@ #define UART1_RX_PIN PA10 #define UART1_TX_PIN PA9 #define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) +#if defined(OMNIBUSF4PRO) #define INVERTER_PIN_UART1_RX PC0 // PC0 has never been used as inverter control on genuine OMNIBUS F4 variants, but leave it as is since some clones actually implement it. #endif @@ -152,12 +157,12 @@ #define USE_UART6 #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 -#if defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4V3) #define INVERTER_PIN_UART6_RX PC8 #define INVERTER_PIN_UART6_TX PC9 #endif -#if defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4V3) &&!(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_RX_PIN PC6 // shared with UART6 TX #define SOFTSERIAL_1_TX_PIN PC6 // shared with UART6 TX @@ -201,7 +206,7 @@ #define USE_SPI_DEVICE_1 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 @@ -210,7 +215,7 @@ #endif #define USE_SPI_DEVICE_3 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define SPI3_NSS_PIN PA15 #else #define SPI3_NSS_PIN PB3 @@ -224,7 +229,7 @@ #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define USE_SDCARD #define USE_SDCARD_SPI @@ -259,7 +264,7 @@ #define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) #define USE_LED_STRIP -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!defined(OMNIBUSF4PRO_LEDSTRIPM5) #define WS2811_PIN PB6 #else #define WS2811_PIN PA1 From 6c858bc6279ffe86ca4f9088878b93f6b22969a4 Mon Sep 17 00:00:00 2001 From: tiriad <42714516+tiriad@users.noreply.github.com> Date: Sun, 1 Dec 2019 17:41:53 +0100 Subject: [PATCH 021/110] update --- src/main/target/OMNIBUSF4/target.c | 4 ++-- src/main/target/OMNIBUSF4/target.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index 5ceb77043a0..233ab8c5265 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -42,7 +42,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3 -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT #elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) @@ -59,7 +59,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT #endif -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!defined(OMNIBUSF4PRO_LEDSTRIPM5) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4) #endif }; diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 0825193bb82..fe2a35cc523 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -162,7 +162,7 @@ #define INVERTER_PIN_UART6_TX PC9 #endif -#if defined(OMNIBUSF4V3) &&!(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) +#if defined(OMNIBUSF4V3) && !(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_RX_PIN PC6 // shared with UART6 TX #define SOFTSERIAL_1_TX_PIN PC6 // shared with UART6 TX @@ -264,7 +264,7 @@ #define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) #define USE_LED_STRIP -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) &&!defined(OMNIBUSF4PRO_LEDSTRIPM5) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) #define WS2811_PIN PB6 #else #define WS2811_PIN PA1 From 8fc0ac3710d44ed48b39d2edb4a303cd13d38758 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 2 Dec 2019 14:24:42 +0100 Subject: [PATCH 022/110] Make Dterm LPF type configurable --- src/main/fc/settings.yaml | 3 +++ src/main/flight/pid.c | 26 ++++++++++++++++++-------- src/main/flight/pid.h | 1 + 3 files changed, 22 insertions(+), 8 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8c583229c8d..50b7cf2add7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1041,6 +1041,9 @@ groups: - name: dterm_lpf_hz min: 0 max: 200 + - name: dterm_lpf_type + field: dterm_lpf_type + table: filter_type - name: use_dterm_fir_filter field: use_dterm_fir_filter type: bool diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f0b943d2985..fdeef29cb05 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -80,7 +80,7 @@ typedef struct { // Rate filtering rateLimitFilter_t axisAccelFilter; pt1Filter_t ptermLpfState; - biquadFilter_t deltaLpfState; + filter_t deltaLpfState; // Dterm notch filtering biquadFilter_t deltaNotchFilter; float stickPosition; @@ -145,7 +145,7 @@ typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 11); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 12); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -216,6 +216,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .dterm_soft_notch_hz = 0, .dterm_soft_notch_cutoff = 1, + .dterm_lpf_type = 1, //Default to BIQUAD .dterm_lpf_hz = 40, .yaw_lpf_hz = 0, .dterm_setpoint_weight = 1.0f, @@ -294,8 +295,14 @@ bool pidInitFilters(void) } // Init other filters - for (int axis = 0; axis < 3; ++ axis) { - biquadFilterInitLPF(&pidState[axis].deltaLpfState, pidProfile()->dterm_lpf_hz, refreshRate); + if (pidProfile()->dterm_lpf_hz) { + for (int axis = 0; axis < 3; ++ axis) { + if (pidProfile()->dterm_lpf_type == FILTER_PT1) { + pt1FilterInit(&pidState[axis].deltaLpfState.pt1, pidProfile()->dterm_lpf_hz, refreshRate * 1e-6f); + } else { + biquadFilterInitLPF(&pidState[axis].deltaLpfState.biquad, pidProfile()->dterm_lpf_hz, refreshRate); + } + } } for (int i = 0; i < XYZ_AXIS_COUNT; i++) { @@ -697,7 +704,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered); // Apply additional lowpass - deltaFiltered = dTermLpfFilterApplyFn(&pidState->deltaLpfState, deltaFiltered); + deltaFiltered = dTermLpfFilterApplyFn((filter_t *) &pidState->deltaLpfState, deltaFiltered); firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered); newDTerm = firFilterApply(&pidState->gyroRateFilter); @@ -1057,10 +1064,13 @@ void pidInit(void) usedPidControllerType = pidProfile()->pidControllerType; } + dTermLpfFilterApplyFn = nullFilterApply; if (pidProfile()->dterm_lpf_hz) { - dTermLpfFilterApplyFn = (filterApplyFnPtr) biquadFilterApply; - } else { - dTermLpfFilterApplyFn = nullFilterApply; + if (pidProfile()->dterm_lpf_type == FILTER_PT1) { + dTermLpfFilterApplyFn = (filterApplyFnPtr) pt1FilterApply; + } else { + dTermLpfFilterApplyFn = (filterApplyFnPtr) biquadFilterApply; + } } if (usedPidControllerType == PID_TYPE_PIFF) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 41f30dbf2d2..baac5061a85 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -107,6 +107,7 @@ typedef struct pidProfile_s { uint16_t dterm_soft_notch_hz; // Dterm Notch frequency uint16_t dterm_soft_notch_cutoff; // Dterm Notch Cutoff frequency + uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD uint8_t dterm_lpf_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish From e52b16c914ffb3f970bcd919e1043a9b819e05b1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 2 Dec 2019 14:52:23 +0100 Subject: [PATCH 023/110] more meaningful name --- src/main/flight/pid.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index fdeef29cb05..94fa4dc9b88 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -80,7 +80,7 @@ typedef struct { // Rate filtering rateLimitFilter_t axisAccelFilter; pt1Filter_t ptermLpfState; - filter_t deltaLpfState; + filter_t dtermLpfState; // Dterm notch filtering biquadFilter_t deltaNotchFilter; float stickPosition; @@ -298,9 +298,9 @@ bool pidInitFilters(void) if (pidProfile()->dterm_lpf_hz) { for (int axis = 0; axis < 3; ++ axis) { if (pidProfile()->dterm_lpf_type == FILTER_PT1) { - pt1FilterInit(&pidState[axis].deltaLpfState.pt1, pidProfile()->dterm_lpf_hz, refreshRate * 1e-6f); + pt1FilterInit(&pidState[axis].dtermLpfState.pt1, pidProfile()->dterm_lpf_hz, refreshRate * 1e-6f); } else { - biquadFilterInitLPF(&pidState[axis].deltaLpfState.biquad, pidProfile()->dterm_lpf_hz, refreshRate); + biquadFilterInitLPF(&pidState[axis].dtermLpfState.biquad, pidProfile()->dterm_lpf_hz, refreshRate); } } } @@ -704,7 +704,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered); // Apply additional lowpass - deltaFiltered = dTermLpfFilterApplyFn((filter_t *) &pidState->deltaLpfState, deltaFiltered); + deltaFiltered = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, deltaFiltered); firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered); newDTerm = firFilterApply(&pidState->gyroRateFilter); From 61381c4c35dceb9b525168a3fc311427005571e4 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 2 Dec 2019 15:36:06 +0100 Subject: [PATCH 024/110] Increase Dterm LPF range --- src/main/blackbox/blackbox.c | 1 + src/main/fc/fc_msp.c | 2 +- src/main/fc/settings.yaml | 2 +- src/main/flight/pid.h | 4 +++- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8b103ebb7a8..cbefa9fcf1b 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1682,6 +1682,7 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit", "%d", pidProfile()->yaw_p_limit); BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", pidProfile()->yaw_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", pidProfile()->dterm_lpf_hz); + BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", pidProfile()->dterm_soft_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ccc95861368..e9b17f00282 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1991,7 +1991,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP_SET_FILTER_CONFIG : if (dataSize >= 5) { gyroConfigMutable()->gyro_soft_lpf_hz = sbufReadU8(src); - pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 255); + pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 500); pidProfileMutable()->yaw_lpf_hz = constrain(sbufReadU16(src), 0, 255); if (dataSize >= 9) { gyroConfigMutable()->gyro_soft_notch_hz_1 = constrain(sbufReadU16(src), 0, 500); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 50b7cf2add7..0bdd4cdf02d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1040,7 +1040,7 @@ groups: max: 900 - name: dterm_lpf_hz min: 0 - max: 200 + max: 500 - name: dterm_lpf_type field: dterm_lpf_type table: filter_type diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index baac5061a85..e9b292af45f 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -107,8 +107,10 @@ typedef struct pidProfile_s { uint16_t dterm_soft_notch_hz; // Dterm Notch frequency uint16_t dterm_soft_notch_cutoff; // Dterm Notch Cutoff frequency + uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD - uint8_t dterm_lpf_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 + uint16_t dterm_lpf_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 + uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish uint8_t yaw_lpf_hz; From 253467008109dec67bd5c66992efd9ed08ecc4d2 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 2 Dec 2019 15:53:46 +0100 Subject: [PATCH 025/110] Add Dterm stage 2 LPF --- src/main/fc/settings.yaml | 6 ++++++ src/main/flight/pid.c | 25 +++++++++++++++++++++++++ src/main/flight/pid.h | 5 ++++- 3 files changed, 35 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0bdd4cdf02d..155a1432e45 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1044,6 +1044,12 @@ groups: - name: dterm_lpf_type field: dterm_lpf_type table: filter_type + - name: dterm_lpf2_hz + min: 0 + max: 500 + - name: dterm_lpf2_type + field: dterm_lpf2_type + table: filter_type - name: use_dterm_fir_filter field: use_dterm_fir_filter type: bool diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 94fa4dc9b88..d70d53fca5d 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -81,6 +81,7 @@ typedef struct { rateLimitFilter_t axisAccelFilter; pt1Filter_t ptermLpfState; filter_t dtermLpfState; + filter_t dtermLpf2State; // Dterm notch filtering biquadFilter_t deltaNotchFilter; float stickPosition; @@ -144,6 +145,7 @@ static EXTENDED_FASTRAM uint8_t usedPidControllerType; typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t axis, float dT); static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; +static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 12); @@ -218,6 +220,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .dterm_soft_notch_cutoff = 1, .dterm_lpf_type = 1, //Default to BIQUAD .dterm_lpf_hz = 40, + .dterm_lpf2_type = 1, //Default to BIQUAD + .dterm_lpf2_hz = 0, // Off by default .yaw_lpf_hz = 0, .dterm_setpoint_weight = 1.0f, .use_dterm_fir_filter = 1, @@ -305,6 +309,17 @@ bool pidInitFilters(void) } } + // Init other filters + if (pidProfile()->dterm_lpf2_hz) { + for (int axis = 0; axis < 3; ++ axis) { + if (pidProfile()->dterm_lpf2_type == FILTER_PT1) { + pt1FilterInit(&pidState[axis].dtermLpf2State.pt1, pidProfile()->dterm_lpf2_hz, refreshRate * 1e-6f); + } else { + biquadFilterInitLPF(&pidState[axis].dtermLpf2State.biquad, pidProfile()->dterm_lpf2_hz, refreshRate); + } + } + } + for (int i = 0; i < XYZ_AXIS_COUNT; i++) { pt1FilterInit(&windupLpf[i], pidProfile()->iterm_relax_cutoff, refreshRate * 1e-6f); } @@ -705,6 +720,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid // Apply additional lowpass deltaFiltered = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, deltaFiltered); + deltaFiltered = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, deltaFiltered); firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered); newDTerm = firFilterApply(&pidState->gyroRateFilter); @@ -1073,6 +1089,15 @@ void pidInit(void) } } + dTermLpf2FilterApplyFn = nullFilterApply; + if (pidProfile()->dterm_lpf2_hz) { + if (pidProfile()->dterm_lpf2_type == FILTER_PT1) { + dTermLpf2FilterApplyFn = (filterApplyFnPtr) pt1FilterApply; + } else { + dTermLpf2FilterApplyFn = (filterApplyFnPtr) biquadFilterApply; + } + } + if (usedPidControllerType == PID_TYPE_PIFF) { pidControllerApplyFn = pidApplyFixedWingRateController; } else if (usedPidControllerType == PID_TYPE_PID) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index e9b292af45f..43f1fae9c26 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -109,7 +109,10 @@ typedef struct pidProfile_s { uint16_t dterm_soft_notch_cutoff; // Dterm Notch Cutoff frequency uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD - uint16_t dterm_lpf_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5 + uint16_t dterm_lpf_hz; + + uint8_t dterm_lpf2_type; // Dterm LPF type: PT1, BIQUAD + uint16_t dterm_lpf2_hz; uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish From 20a618295f6dfc8ea29c6f39a86310e917990529 Mon Sep 17 00:00:00 2001 From: tiriad <42714516+tiriad@users.noreply.github.com> Date: Tue, 3 Dec 2019 00:05:17 +0100 Subject: [PATCH 026/110] Update product string to DysF4Pro for DysF4ProV2 instead OmnibusF4 --- src/main/target/OMNIBUSF4/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index fe2a35cc523..991fb6c4ab4 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -38,7 +38,7 @@ #define TARGET_BOARD_IDENTIFIER "OBF4" #endif -#if defined(DYSF4PRO) +#if defined(DYSF4PRO) || defined(DYSF4PROV2) #define USBD_PRODUCT_STRING "DysF4Pro" #else #define USBD_PRODUCT_STRING "Omnibus F4" From 654af96b1b1c1df85f4c62f2dde571b6a9121325 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 3 Dec 2019 09:56:35 +0100 Subject: [PATCH 027/110] Free some FASTRAM on F3 --- src/main/sensors/acceleration.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 4a605d8b2f0..5a1cdd8b6d3 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -78,11 +78,11 @@ STATIC_FASTRAM filter_t accFilter[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr accSoftLpfFilterApplyFn; STATIC_FASTRAM void *accSoftLpfFilter[XYZ_AXIS_COUNT]; -STATIC_FASTRAM pt1Filter_t accVibeFloorFilter[XYZ_AXIS_COUNT]; -STATIC_FASTRAM pt1Filter_t accVibeFilter[XYZ_AXIS_COUNT]; +static EXTENDED_FASTRAM pt1Filter_t accVibeFloorFilter[XYZ_AXIS_COUNT]; +static EXTENDED_FASTRAM pt1Filter_t accVibeFilter[XYZ_AXIS_COUNT]; -STATIC_FASTRAM filterApplyFnPtr accNotchFilterApplyFn; -STATIC_FASTRAM void *accNotchFilter[XYZ_AXIS_COUNT]; +static EXTENDED_FASTRAM filterApplyFnPtr accNotchFilterApplyFn; +static EXTENDED_FASTRAM void *accNotchFilter[XYZ_AXIS_COUNT]; PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 3); From 4981cbe3b12fbbe9ff2004a0a14299c6d3564174 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 3 Dec 2019 11:02:41 +0100 Subject: [PATCH 028/110] Put extra data into blackbox header --- src/main/blackbox/blackbox.c | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index cbefa9fcf1b..c4f972bca10 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1683,12 +1683,20 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", pidProfile()->yaw_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", pidProfile()->dterm_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type); + BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_hz", "%d", pidProfile()->dterm_lpf2_hz); + BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_type", "%d", pidProfile()->dterm_lpf2_type); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", pidProfile()->dterm_soft_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband); BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_soft_lpf_hz); + BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_soft_lpf_type); + BLACKBOX_PRINT_HEADER_LINE("gyro_lpf2_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz); + BLACKBOX_PRINT_HEADER_LINE("dyn_notch_width_percent", "%d", gyroConfig()->dyn_notch_width_percent); + BLACKBOX_PRINT_HEADER_LINE("dyn_notch_range", "%d", gyroConfig()->dyn_notch_range); + BLACKBOX_PRINT_HEADER_LINE("dyn_notch_q", "%d", gyroConfig()->dyn_notch_q); + BLACKBOX_PRINT_HEADER_LINE("dyn_notch_min_hz", "%d", gyroConfig()->dyn_notch_min_hz); BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_hz_2); BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1, From 7a001b4b16752ca906f12157fb421c8f591a23ac Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 3 Dec 2019 12:45:32 +0100 Subject: [PATCH 029/110] Disable not used targets --- Makefile | 8 ++++---- build_docs.sh | 1 - docs/1wire.md | 2 +- docs/Board - ChebuzzF3.md | 7 ------- docs/LedStrip.md | 2 +- fake_travis_build.sh | 2 -- make/release.mk | 2 +- src/main/fc/fc_init.c | 6 +----- src/main/target/ALIENFLIGHTF3/{target.mk => target.mk_} | 0 src/main/target/ALIENFLIGHTF4/{target.mk => target.mk_} | 0 src/main/target/ANYFCM7/{target.mk => target.mk_} | 0 src/main/target/CHEBUZZF3/{target.mk => target.mk_} | 0 src/main/target/KISSFC/{target.mk => target.mk_} | 0 src/main/target/KROOZX/{target.mk => target.mk_} | 0 src/main/target/RADIX/{target.mk => target.mk_} | 0 src/main/target/YUPIF4/{YUPIF4MINI.mk => YUPIF4MINI.mk_} | 0 src/main/target/YUPIF4/{YUPIF4R2.mk => YUPIF4R2.mk_} | 0 src/main/target/YUPIF4/{target.mk => target.mk_} | 0 18 files changed, 8 insertions(+), 22 deletions(-) rename src/main/target/ALIENFLIGHTF3/{target.mk => target.mk_} (100%) rename src/main/target/ALIENFLIGHTF4/{target.mk => target.mk_} (100%) rename src/main/target/ANYFCM7/{target.mk => target.mk_} (100%) rename src/main/target/CHEBUZZF3/{target.mk => target.mk_} (100%) rename src/main/target/KISSFC/{target.mk => target.mk_} (100%) rename src/main/target/KROOZX/{target.mk => target.mk_} (100%) rename src/main/target/RADIX/{target.mk => target.mk_} (100%) rename src/main/target/YUPIF4/{YUPIF4MINI.mk => YUPIF4MINI.mk_} (100%) rename src/main/target/YUPIF4/{YUPIF4R2.mk => YUPIF4R2.mk_} (100%) rename src/main/target/YUPIF4/{target.mk => target.mk_} (100%) diff --git a/Makefile b/Makefile index d87fea00f1c..9ff4b3ae94c 100644 --- a/Makefile +++ b/Makefile @@ -126,13 +126,13 @@ else $(error Unknown target MCU specified.) endif -GROUP_1_TARGETS := ALIENFLIGHTF3 ALIENFLIGHTF4 AIRHEROF3 AIRHEROF3_QUAD COLIBRI_RACE LUX_RACE SPARKY REVO SPARKY2 COLIBRI KISSFC FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD +GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD COLIBRI_RACE LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 -GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 ALIENFLIGHTNGF7 PIXRACER YUPIF4 YUPIF4MINI YUPIF4R2 YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX -GROUP_5_TARGETS := ASGARD32F7 CHEBUZZF3 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD +GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX +GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 -GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO +GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO GROUP_8_TARGETS := MATEKF765 GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) diff --git a/build_docs.sh b/build_docs.sh index 918430eacae..70c2cc45cfb 100755 --- a/build_docs.sh +++ b/build_docs.sh @@ -29,7 +29,6 @@ doc_files=( 'Migrating from baseflight.md' 'Boards.md' 'Board - AlienFlight.md' - 'Board - ChebuzzF3.md' 'Board - ColibriRace.md' 'Board - Motolab.md' 'Board - Paris Air Hero 32.md' diff --git a/docs/1wire.md b/docs/1wire.md index c64760e775c..94094637cee 100644 --- a/docs/1wire.md +++ b/docs/1wire.md @@ -58,7 +58,7 @@ The following parameters can be used to enable and configure this in the related ``` // Define your esc hardware - #if defined(STM32F3DISCOVERY) && !(defined(CHEBUZZF3)) + #if defined(STM32F3DISCOVERY) const escHardware_t escHardware[ESC_COUNT] = { { GPIOD, 12 }, { GPIOD, 13 }, diff --git a/docs/Board - ChebuzzF3.md b/docs/Board - ChebuzzF3.md index c729207814d..7df5604125b 100644 --- a/docs/Board - ChebuzzF3.md +++ b/docs/Board - ChebuzzF3.md @@ -1,10 +1,3 @@ -# Board - ChebuzzF3 - -The ChebuzzF3 is a daugter board which connects to the bottom of an STM32F3Discovery board and provides pin headers and ports for various FC connections. - -All connections were traced using a multimeter and then verified against the TauLabs source code using the revision linked. - -https://github.com/TauLabs/TauLabs/blob/816760dec2a20db7fb9ec1a505add240e696c31f/flight/targets/flyingf3/board-info/board_hw_defs.c ## Connections diff --git a/docs/LedStrip.md b/docs/LedStrip.md index 46d463754cd..3e2a9b11d98 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -50,7 +50,7 @@ from another BEC. Just ensure that the GROUND is the same for all BEC outputs a | Target | Pin | LED Strip | Signal | | --------------------- | ---- | --------- | -------| -| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 | +| F3Discovery | PB8 | Data In | PB8 | | Sparky | PWM5 | Data In | PA6 | If you have LEDs that are intermittent, flicker or show the wrong colors then drop the VIN to less than 4.7v, e.g. by using an inline diff --git a/fake_travis_build.sh b/fake_travis_build.sh index f56adee40e6..4380008800e 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -2,7 +2,6 @@ targets=("PUBLISHMETA=True" \ "RUNTESTS=True" \ - "TARGET=CHEBUZZF3" \ "TARGET=COLIBRI_RACE" \ "TARGET=SPRACINGF3" \ "TARGET=SPRACINGF3EVO" \ @@ -11,7 +10,6 @@ targets=("PUBLISHMETA=True" \ "TARGET=RMDO" \ "TARGET=SPARKY" \ "TARGET=STM32F3DISCOVERY" \ - "TARGET=ALIENFLIGHTF3"\ "TARGET=RCEXPLORERF3" ) #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/make/release.mk b/make/release.mk index a4ecbd534bf..2933b4fe169 100644 --- a/make/release.mk +++ b/make/release.mk @@ -1,7 +1,7 @@ RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD RELEASE_TARGETS += COLIBRI_RACE LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 -RELEASE_TARGETS += QUANTON REVO SPARKY2 YUPIF4 YUPIF4R2 YUPIF4MINI KROOZX PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 +RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO RELEASE_TARGETS += ALIENFLIGHTNGF7 RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 7b4736d5a92..e936274f77f 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -217,12 +217,8 @@ void init(void) // Latch active features to be used for feature() in the remainder of init(). latchActiveFeatures(); - -#ifdef ALIENFLIGHTF3 - ledInit(hardwareRevision == AFF3_REV_1 ? false : true); -#else + ledInit(false); -#endif #ifdef USE_EXTI EXTIInit(); diff --git a/src/main/target/ALIENFLIGHTF3/target.mk b/src/main/target/ALIENFLIGHTF3/target.mk_ similarity index 100% rename from src/main/target/ALIENFLIGHTF3/target.mk rename to src/main/target/ALIENFLIGHTF3/target.mk_ diff --git a/src/main/target/ALIENFLIGHTF4/target.mk b/src/main/target/ALIENFLIGHTF4/target.mk_ similarity index 100% rename from src/main/target/ALIENFLIGHTF4/target.mk rename to src/main/target/ALIENFLIGHTF4/target.mk_ diff --git a/src/main/target/ANYFCM7/target.mk b/src/main/target/ANYFCM7/target.mk_ similarity index 100% rename from src/main/target/ANYFCM7/target.mk rename to src/main/target/ANYFCM7/target.mk_ diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk_ similarity index 100% rename from src/main/target/CHEBUZZF3/target.mk rename to src/main/target/CHEBUZZF3/target.mk_ diff --git a/src/main/target/KISSFC/target.mk b/src/main/target/KISSFC/target.mk_ similarity index 100% rename from src/main/target/KISSFC/target.mk rename to src/main/target/KISSFC/target.mk_ diff --git a/src/main/target/KROOZX/target.mk b/src/main/target/KROOZX/target.mk_ similarity index 100% rename from src/main/target/KROOZX/target.mk rename to src/main/target/KROOZX/target.mk_ diff --git a/src/main/target/RADIX/target.mk b/src/main/target/RADIX/target.mk_ similarity index 100% rename from src/main/target/RADIX/target.mk rename to src/main/target/RADIX/target.mk_ diff --git a/src/main/target/YUPIF4/YUPIF4MINI.mk b/src/main/target/YUPIF4/YUPIF4MINI.mk_ similarity index 100% rename from src/main/target/YUPIF4/YUPIF4MINI.mk rename to src/main/target/YUPIF4/YUPIF4MINI.mk_ diff --git a/src/main/target/YUPIF4/YUPIF4R2.mk b/src/main/target/YUPIF4/YUPIF4R2.mk_ similarity index 100% rename from src/main/target/YUPIF4/YUPIF4R2.mk rename to src/main/target/YUPIF4/YUPIF4R2.mk_ diff --git a/src/main/target/YUPIF4/target.mk b/src/main/target/YUPIF4/target.mk_ similarity index 100% rename from src/main/target/YUPIF4/target.mk rename to src/main/target/YUPIF4/target.mk_ From a3c4ae2a349e1894a1815dead4bb6c4e7f76fc56 Mon Sep 17 00:00:00 2001 From: hali9 Date: Tue, 3 Dec 2019 21:00:01 +0100 Subject: [PATCH 030/110] Update navigation.c --- src/main/navigation/navigation.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 929e8683a2e..b5468e0a69b 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2084,7 +2084,8 @@ float getFinalRTHAltitude(void) static void updateDesiredRTHAltitude(void) { if (ARMING_FLAG(ARMED)) { - if (!(navGetStateFlags(posControl.navState) & NAV_AUTO_RTH)) { + if (!((navGetStateFlags(posControl.navState) & NAV_AUTO_RTH) + || ((navGetStateFlags(posControl.navState) & NAV_AUTO_WP) && posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_RTH))) { switch (navConfig()->general.flags.rth_alt_control_mode) { case NAV_RTH_NO_ALT: posControl.rthState.rthInitialAltitude = posControl.actualState.abs.pos.z; From f871041dbb2a4425d4d7c65062966c92e3a9a54b Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Dec 2019 14:42:44 +0100 Subject: [PATCH 031/110] Gyro LPF Stage2 configurable type --- src/main/common/filter.c | 25 ------------------------- src/main/common/filter.h | 5 +---- src/main/fc/settings.yaml | 3 +++ src/main/sensors/gyro.c | 24 +++++++++++++++++++----- src/main/sensors/gyro.h | 1 + 5 files changed, 24 insertions(+), 34 deletions(-) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index a0c19d20f3b..86c098343a1 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -126,31 +126,6 @@ void biquadFilterInitLPF(biquadFilter_t *filter, uint16_t filterFreq, uint32_t s biquadFilterInit(filter, filterFreq, samplingIntervalUs, BIQUAD_Q, FILTER_LPF); } -// ledvinap's proposed RC+FIR2 Biquad-- 1st order IIR, RC filter k -void biquadRCFIR2FilterInit(biquadFilter_t *filter, uint16_t f_cut, uint32_t samplingIntervalUs) -{ - if (f_cut < (1000000 / samplingIntervalUs / 2)) { - const float dT = (float) samplingIntervalUs * 0.000001f; - const float RC = 1.0f / ( 2.0f * M_PIf * f_cut ); - const float k = dT / (RC + dT); - filter->b0 = k / 2; - filter->b1 = k / 2; - filter->b2 = 0; - filter->a1 = -(1 - k); - filter->a2 = 0; - } else { - filter->b0 = 1.0f; - filter->b1 = 0.0f; - filter->b2 = 0.0f; - filter->a1 = 0.0f; - filter->a2 = 0.0f; - } - - // zero initial samples - filter->x1 = filter->x2 = 0; - filter->y1 = filter->y2 = 0; -} - void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs, float Q, biquadFilterType_e filterType) { // Check for Nyquist frequency and if it's not possible to initialize filter as requested - set to no filtering at all diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 3ee3d349ebb..6114393d766 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -40,8 +40,7 @@ typedef union { typedef enum { FILTER_PT1 = 0, - FILTER_BIQUAD, - FILTER_FIR, + FILTER_BIQUAD } filterType_e; typedef enum { @@ -72,8 +71,6 @@ void pt1FilterReset(pt1Filter_t *filter, float input); void rateLimitFilterInit(rateLimitFilter_t *filter); float rateLimitFilterApply4(rateLimitFilter_t *filter, float input, float rate_limit, float dT); -void biquadRCFIR2FilterInit(biquadFilter_t *filter, uint16_t f_cut, uint32_t samplingIntervalUs); - void biquadFilterInitNotch(biquadFilter_t *filter, uint32_t samplingIntervalUs, uint16_t filterFreq, uint16_t cutoffHz); void biquadFilterInitLPF(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs); void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs, float Q, biquadFilterType_e filterType); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8c583229c8d..66524bd93d7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -183,6 +183,9 @@ groups: field: gyro_stage2_lowpass_hz min: 0 max: 500 + - name: gyro_stage2_lowpass_type + field: gyro_stage2_lowpass_type + table: filter_type - name: dyn_notch_width_percent field: dyn_notch_width_percent condition: USE_DYNAMIC_FILTERS diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 1d76a125d6a..9e3d3212593 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -120,6 +120,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_soft_notch_hz_2 = 0, .gyro_soft_notch_cutoff_2 = 1, .gyro_stage2_lowpass_hz = 0, + .gyro_stage2_lowpass_type = FILTER_BIQUAD, .dyn_notch_width_percent = 8, .dyn_notch_range = DYN_NOTCH_RANGE_MEDIUM, .dyn_notch_q = 120, @@ -337,15 +338,28 @@ void gyroInitFilters(void) STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; notchFilter2ApplyFn = nullFilterApply; - STATIC_FASTRAM biquadFilter_t gyroFilterStage2[XYZ_AXIS_COUNT]; + STATIC_FASTRAM filter_t gyroFilterStage2[XYZ_AXIS_COUNT]; gyroFilterStage2ApplyFn = nullFilterApply; if (gyroConfig()->gyro_stage2_lowpass_hz > 0) { - gyroFilterStage2ApplyFn = (filterApplyFnPtr)biquadFilterApply; - for (int axis = 0; axis < 3; axis++) { - stage2Filter[axis] = &gyroFilterStage2[axis]; - biquadRCFIR2FilterInit(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); + switch (gyroConfig()->gyro_stage2_lowpass_type) + { + case FILTER_PT1: + softLpfFilterApplyFn = (filterApplyFnPtr)pt1FilterApply; + for (int axis = 0; axis < 3; axis++) { + stage2Filter[axis] = &gyroFilterStage2[axis].pt1; + pt1FilterInit(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); + } + break; + case FILTER_BIQUAD: + gyroFilterStage2ApplyFn = (filterApplyFnPtr)biquadFilterApply; + for (int axis = 0; axis < 3; axis++) { + stage2Filter[axis] = &gyroFilterStage2[axis].biquad; + biquadFilterInitLPF(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); + } + break; } + } if (gyroConfig()->gyro_soft_lpf_hz) { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 9c1d627030c..3d9a3acd3b4 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -70,6 +70,7 @@ typedef struct gyroConfig_s { uint16_t gyro_soft_notch_hz_2; uint16_t gyro_soft_notch_cutoff_2; uint16_t gyro_stage2_lowpass_hz; + uint8_t gyro_stage2_lowpass_type; uint8_t dyn_notch_width_percent; uint8_t dyn_notch_range; uint16_t dyn_notch_q; From ad74cbfdf2d8b9e17201a300d2168407d45740fe Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Dec 2019 14:50:37 +0100 Subject: [PATCH 032/110] Rename variables for more meaningfull names --- src/main/sensors/gyro.c | 44 ++++++++++++++++++++--------------------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 9e3d3212593..448fa9f3cc8 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -81,17 +81,17 @@ STATIC_FASTRAM int16_t gyroTemperature0; STATIC_FASTRAM_UNIT_TESTED zeroCalibrationVector_t gyroCalibration; STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT]; -STATIC_FASTRAM filterApplyFnPtr softLpfFilterApplyFn; -STATIC_FASTRAM void *softLpfFilter[XYZ_AXIS_COUNT]; +STATIC_FASTRAM filterApplyFnPtr gyroLpfApplyFn; +STATIC_FASTRAM void *gyroLpfState[XYZ_AXIS_COUNT]; + +STATIC_FASTRAM filterApplyFnPtr gyroLpf2ApplyFn; +STATIC_FASTRAM void *gyroLpf2State[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr notchFilter1ApplyFn; STATIC_FASTRAM void *notchFilter1[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr notchFilter2ApplyFn; STATIC_FASTRAM void *notchFilter2[XYZ_AXIS_COUNT]; -STATIC_FASTRAM filterApplyFnPtr gyroFilterStage2ApplyFn; -STATIC_FASTRAM void *stage2Filter[XYZ_AXIS_COUNT]; - #ifdef USE_DYNAMIC_FILTERS #define DYNAMIC_NOTCH_DEFAULT_CENTER_HZ 350 @@ -104,7 +104,7 @@ static EXTENDED_FASTRAM biquadFilter_t notchFilterDyn2[XYZ_AXIS_COUNT]; EXTENDED_FASTRAM gyroAnalyseState_t gyroAnalyseState; #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 6); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 7); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = GYRO_LPF_42HZ, // 42HZ value is defined for Invensense/TDK gyros @@ -330,7 +330,7 @@ bool gyroInit(void) void gyroInitFilters(void) { STATIC_FASTRAM filter_t gyroFilterLPF[XYZ_AXIS_COUNT]; - softLpfFilterApplyFn = nullFilterApply; + gyroLpfApplyFn = nullFilterApply; STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; notchFilter1ApplyFn = nullFilterApply; @@ -339,23 +339,23 @@ void gyroInitFilters(void) notchFilter2ApplyFn = nullFilterApply; STATIC_FASTRAM filter_t gyroFilterStage2[XYZ_AXIS_COUNT]; - gyroFilterStage2ApplyFn = nullFilterApply; + gyroLpf2ApplyFn = nullFilterApply; if (gyroConfig()->gyro_stage2_lowpass_hz > 0) { switch (gyroConfig()->gyro_stage2_lowpass_type) { case FILTER_PT1: - softLpfFilterApplyFn = (filterApplyFnPtr)pt1FilterApply; + gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - stage2Filter[axis] = &gyroFilterStage2[axis].pt1; - pt1FilterInit(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); + gyroLpf2State[axis] = &gyroFilterStage2[axis].pt1; + pt1FilterInit(gyroLpf2State[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); } break; case FILTER_BIQUAD: - gyroFilterStage2ApplyFn = (filterApplyFnPtr)biquadFilterApply; + gyroLpf2ApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { - stage2Filter[axis] = &gyroFilterStage2[axis].biquad; - biquadFilterInitLPF(stage2Filter[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); + gyroLpf2State[axis] = &gyroFilterStage2[axis].biquad; + biquadFilterInitLPF(gyroLpf2State[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); } break; } @@ -367,17 +367,17 @@ void gyroInitFilters(void) switch (gyroConfig()->gyro_soft_lpf_type) { case FILTER_PT1: - softLpfFilterApplyFn = (filterApplyFnPtr)pt1FilterApply; + gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - softLpfFilter[axis] = &gyroFilterLPF[axis].pt1; - pt1FilterInit(softLpfFilter[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()* 1e-6f); + gyroLpfState[axis] = &gyroFilterLPF[axis].pt1; + pt1FilterInit(gyroLpfState[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()* 1e-6f); } break; case FILTER_BIQUAD: - softLpfFilterApplyFn = (filterApplyFnPtr)biquadFilterApply; + gyroLpfApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { - softLpfFilter[axis] = &gyroFilterLPF[axis].biquad; - biquadFilterInitLPF(softLpfFilter[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()); + gyroLpfState[axis] = &gyroFilterLPF[axis].biquad; + biquadFilterInitLPF(gyroLpfState[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()); } break; } @@ -478,8 +478,8 @@ void FAST_CODE NOINLINE gyroUpdate() DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf)); - gyroADCf = gyroFilterStage2ApplyFn(stage2Filter[axis], gyroADCf); - gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf); + gyroADCf = gyroLpf2ApplyFn(gyroLpf2State[axis], gyroADCf); + gyroADCf = gyroLpfApplyFn(gyroLpfState[axis], gyroADCf); gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf); gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf); From 03e5b74bf28de7d08ab951282a7121acad372aa7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Dec 2019 15:03:27 +0100 Subject: [PATCH 033/110] Refactor gyro LPFs state holders --- src/main/sensors/gyro.c | 25 +++++++++---------------- 1 file changed, 9 insertions(+), 16 deletions(-) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 448fa9f3cc8..adc83183252 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -82,10 +82,10 @@ STATIC_FASTRAM_UNIT_TESTED zeroCalibrationVector_t gyroCalibration; STATIC_FASTRAM int32_t gyroADC[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr gyroLpfApplyFn; -STATIC_FASTRAM void *gyroLpfState[XYZ_AXIS_COUNT]; +STATIC_FASTRAM filter_t gyroLpfState[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr gyroLpf2ApplyFn; -STATIC_FASTRAM void *gyroLpf2State[XYZ_AXIS_COUNT]; +STATIC_FASTRAM filter_t gyroLpf2State[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr notchFilter1ApplyFn; STATIC_FASTRAM void *notchFilter1[XYZ_AXIS_COUNT]; @@ -329,8 +329,8 @@ bool gyroInit(void) void gyroInitFilters(void) { - STATIC_FASTRAM filter_t gyroFilterLPF[XYZ_AXIS_COUNT]; gyroLpfApplyFn = nullFilterApply; + gyroLpf2ApplyFn = nullFilterApply; STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; notchFilter1ApplyFn = nullFilterApply; @@ -338,24 +338,19 @@ void gyroInitFilters(void) STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; notchFilter2ApplyFn = nullFilterApply; - STATIC_FASTRAM filter_t gyroFilterStage2[XYZ_AXIS_COUNT]; - gyroLpf2ApplyFn = nullFilterApply; - if (gyroConfig()->gyro_stage2_lowpass_hz > 0) { switch (gyroConfig()->gyro_stage2_lowpass_type) { case FILTER_PT1: gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - gyroLpf2State[axis] = &gyroFilterStage2[axis].pt1; - pt1FilterInit(gyroLpf2State[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); + pt1FilterInit(&gyroLpf2State[axis].pt1, gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); } break; case FILTER_BIQUAD: gyroLpf2ApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { - gyroLpf2State[axis] = &gyroFilterStage2[axis].biquad; - biquadFilterInitLPF(gyroLpf2State[axis], gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); + biquadFilterInitLPF(&gyroLpf2State[axis].biquad, gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); } break; } @@ -369,15 +364,13 @@ void gyroInitFilters(void) case FILTER_PT1: gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - gyroLpfState[axis] = &gyroFilterLPF[axis].pt1; - pt1FilterInit(gyroLpfState[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()* 1e-6f); + pt1FilterInit(&gyroLpfState[axis].pt1, gyroConfig()->gyro_soft_lpf_hz, getLooptime()* 1e-6f); } break; case FILTER_BIQUAD: gyroLpfApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { - gyroLpfState[axis] = &gyroFilterLPF[axis].biquad; - biquadFilterInitLPF(gyroLpfState[axis], gyroConfig()->gyro_soft_lpf_hz, getLooptime()); + biquadFilterInitLPF(&gyroLpfState[axis].biquad, gyroConfig()->gyro_soft_lpf_hz, getLooptime()); } break; } @@ -478,8 +471,8 @@ void FAST_CODE NOINLINE gyroUpdate() DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf)); - gyroADCf = gyroLpf2ApplyFn(gyroLpf2State[axis], gyroADCf); - gyroADCf = gyroLpfApplyFn(gyroLpfState[axis], gyroADCf); + gyroADCf = gyroLpf2ApplyFn((filter_t *) &gyroLpf2State[axis], gyroADCf); + gyroADCf = gyroLpfApplyFn((filter_t *) &gyroLpfState[axis], gyroADCf); gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf); gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf); From 670145e0ac35141af9566bb356435d9cb22a53fa Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Dec 2019 15:59:40 +0100 Subject: [PATCH 034/110] Simplify gyro filter initialization --- src/main/sensors/gyro.c | 54 +++++++++++++++-------------------------- 1 file changed, 19 insertions(+), 35 deletions(-) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index adc83183252..9697d7f1bd2 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -327,54 +327,38 @@ bool gyroInit(void) return true; } -void gyroInitFilters(void) +static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint8_t type, uint16_t cutoff) { - gyroLpfApplyFn = nullFilterApply; - gyroLpf2ApplyFn = nullFilterApply; - - STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; - notchFilter1ApplyFn = nullFilterApply; - - STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; - notchFilter2ApplyFn = nullFilterApply; - - if (gyroConfig()->gyro_stage2_lowpass_hz > 0) { - switch (gyroConfig()->gyro_stage2_lowpass_type) + *applyFn = nullFilterApply; + if (cutoff > 0) { + switch (type) { case FILTER_PT1: - gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; + *applyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - pt1FilterInit(&gyroLpf2State[axis].pt1, gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()* 1e-6f); + pt1FilterInit(&state[axis].pt1, cutoff, getLooptime()* 1e-6f); } break; case FILTER_BIQUAD: - gyroLpf2ApplyFn = (filterApplyFnPtr)biquadFilterApply; + *applyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { - biquadFilterInitLPF(&gyroLpf2State[axis].biquad, gyroConfig()->gyro_stage2_lowpass_hz, getLooptime()); + biquadFilterInitLPF(&state[axis].biquad, cutoff, getLooptime()); } break; } - } +} - if (gyroConfig()->gyro_soft_lpf_hz) { - - switch (gyroConfig()->gyro_soft_lpf_type) - { - case FILTER_PT1: - gyroLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; - for (int axis = 0; axis < 3; axis++) { - pt1FilterInit(&gyroLpfState[axis].pt1, gyroConfig()->gyro_soft_lpf_hz, getLooptime()* 1e-6f); - } - break; - case FILTER_BIQUAD: - gyroLpfApplyFn = (filterApplyFnPtr)biquadFilterApply; - for (int axis = 0; axis < 3; axis++) { - biquadFilterInitLPF(&gyroLpfState[axis].biquad, gyroConfig()->gyro_soft_lpf_hz, getLooptime()); - } - break; - } - } +void gyroInitFilters(void) +{ + STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; + notchFilter1ApplyFn = nullFilterApply; + + STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; + notchFilter2ApplyFn = nullFilterApply; + + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_stage2_lowpass_type, gyroConfig()->gyro_stage2_lowpass_hz); + initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_soft_lpf_type, gyroConfig()->gyro_soft_lpf_hz); if (gyroConfig()->gyro_soft_notch_hz_1) { notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply; From e5567da9e37657ab7824240724ae3a37db820ed0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Wed, 4 Dec 2019 18:55:48 +0100 Subject: [PATCH 035/110] RPM filters (#5188) * Empty framework to apply RPM filter * Init gyro RPM filter * Entry point for Dterm filter * RPM filter implementation * Bugfixes * Fix Dterm fileter bank * Save RPM filter configuration in blackbox header * Debug RPM frequency * Disable PWM servo driver on all F3 boards * Move RPM filter to ITCM_RAM * Disable target COLIBRI_RACE as it's out of RAM * Drop FEATURE in favor of just settings --- Makefile | 2 +- fake_travis_build.sh | 1 - make/release.mk | 2 +- make/source.mk | 1 + src/main/blackbox/blackbox.c | 11 + src/main/build/debug.h | 2 + src/main/config/parameter_group_ids.h | 3 +- src/main/fc/cli.c | 2 +- src/main/fc/config.h | 2 +- src/main/fc/fc_init.c | 9 + src/main/fc/fc_tasks.c | 9 + src/main/fc/settings.c | 1 + src/main/fc/settings.yaml | 42 +++- src/main/flight/pid.c | 5 + src/main/flight/rpm_filter.c | 232 ++++++++++++++++++ src/main/flight/rpm_filter.h | 53 ++++ src/main/scheduler/scheduler.h | 3 + src/main/sensors/esc_sensor.c | 11 +- src/main/sensors/esc_sensor.h | 3 + src/main/sensors/gyro.c | 8 + .../COLIBRI_RACE/{target.mk => target.mk_} | 0 src/main/target/MATEKF722SE/target.h | 2 +- src/main/target/OMNIBUS/target.h | 2 - src/main/target/SPRACINGF3NEO/target.h | 1 - src/main/target/common_post.h | 5 + 25 files changed, 400 insertions(+), 12 deletions(-) create mode 100644 src/main/flight/rpm_filter.c create mode 100644 src/main/flight/rpm_filter.h rename src/main/target/COLIBRI_RACE/{target.mk => target.mk_} (100%) diff --git a/Makefile b/Makefile index 9ff4b3ae94c..269c6b78326 100644 --- a/Makefile +++ b/Makefile @@ -126,7 +126,7 @@ else $(error Unknown target MCU specified.) endif -GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD COLIBRI_RACE LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD +GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 4380008800e..8e453e119df 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -2,7 +2,6 @@ targets=("PUBLISHMETA=True" \ "RUNTESTS=True" \ - "TARGET=COLIBRI_RACE" \ "TARGET=SPRACINGF3" \ "TARGET=SPRACINGF3EVO" \ "TARGET=LUX_RACE" \ diff --git a/make/release.mk b/make/release.mk index 2933b4fe169..36f85ebc26c 100644 --- a/make/release.mk +++ b/make/release.mk @@ -1,6 +1,6 @@ RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD -RELEASE_TARGETS += COLIBRI_RACE LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 +RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO RELEASE_TARGETS += ALIENFLIGHTNGF7 diff --git a/make/source.mk b/make/source.mk index a7197a93a3d..bbfbc70ee0d 100644 --- a/make/source.mk +++ b/make/source.mk @@ -97,6 +97,7 @@ COMMON_SRC = \ flight/servos.c \ flight/wind_estimator.c \ flight/gyroanalyse.c \ + flight/rpm_filter.c \ io/beeper.c \ io/esc_serialshot.c \ io/frsky_osd.c \ diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8b103ebb7a8..7d5aaee7985 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -58,6 +58,7 @@ #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" +#include "flight/rpm_filter.h" #include "io/beeper.h" #include "io/gps.h" @@ -1711,6 +1712,16 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch); +#ifdef USE_RPM_FILTER + BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_filter_enabled", "%d", rpmFilterConfig()->gyro_filter_enabled); + BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_harmonics", "%d", rpmFilterConfig()->gyro_harmonics); + BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_min_hz", "%d", rpmFilterConfig()->gyro_min_hz); + BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_q", "%d", rpmFilterConfig()->gyro_q); + BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_filter_enabled", "%d", rpmFilterConfig()->dterm_filter_enabled); + BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_harmonics", "%d", rpmFilterConfig()->dterm_harmonics); + BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_min_hz", "%d", rpmFilterConfig()->dterm_min_hz); + BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_q", "%d", rpmFilterConfig()->dterm_q); +#endif default: return true; } diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 8da3ad3f9e1..4b590d5af4b 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -65,5 +65,7 @@ typedef enum { DEBUG_ACC, DEBUG_ITERM_RELAX, DEBUG_ERPM, + DEBUG_RPM_FILTER, + DEBUG_RPM_FREQ, DEBUG_COUNT } debugType_e; diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 39c4420a8a1..8cb31ec3dac 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -109,7 +109,8 @@ #define PG_GENERAL_SETTINGS 1019 #define PG_GLOBAL_FUNCTIONS 1020 #define PG_ESC_SENSOR_CONFIG 1021 -#define PG_INAV_END 1021 +#define PG_RPM_FILTER_CONFIG 1022 +#define PG_INAV_END 1022 // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 95641b27f83..e5ccef4bfa8 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -144,7 +144,7 @@ static bool commandBatchError = false; // sync this with features_e static const char * const featureNames[] = { "THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP", - "DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "", + "DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "RPM_FILTERS", "", "TELEMETRY", "CURRENT_METER", "3D", "", "", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "", "BLACKBOX", "", "TRANSPONDER", "AIRMODE", diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 62b3fb89e5c..06b52bde519 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -44,7 +44,7 @@ typedef enum { FEATURE_DYNAMIC_FILTERS = 1 << 5, // was FEATURE_SERVO_TILT FEATURE_SOFTSERIAL = 1 << 6, FEATURE_GPS = 1 << 7, - FEATURE_UNUSED_3 = 1 << 8, // was FEATURE_FAILSAFE + FEATURE_UNUSED_3 = 1 << 8, // was FEATURE_FAILSAFE FEATURE_UNUSED_4 = 1 << 9, // was FEATURE_SONAR FEATURE_TELEMETRY = 1 << 10, FEATURE_CURRENT_METER = 1 << 11, diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index e936274f77f..e1718b26d38 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -90,6 +90,7 @@ #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" +#include "flight/rpm_filter.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/beeper.h" @@ -644,5 +645,13 @@ void init(void) } #endif +#ifdef USE_RPM_FILTER + disableRpmFilters(); + if (STATE(ESC_SENSOR_ENABLED) && (rpmFilterConfig()->gyro_filter_enabled || rpmFilterConfig()->dterm_filter_enabled)) { + rpmFiltersInit(); + setTaskEnabled(TASK_RPM_FILTER, true); + } +#endif + systemState |= SYSTEM_STATE_READY; } diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 643ba568263..dc50a4126e1 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -47,6 +47,7 @@ #include "flight/mixer.h" #include "flight/pid.h" #include "flight/wind_estimator.h" +#include "flight/rpm_filter.h" #include "navigation/navigation.h" @@ -561,4 +562,12 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_IDLE, }, #endif +#ifdef USE_RPM_FILTER + [TASK_RPM_FILTER] = { + .taskName = "RPM", + .taskFunc = rpmFilterUpdateTask, + .desiredPeriod = TASK_PERIOD_HZ(RPM_FILTER_UPDATE_RATE_HZ), // 300Hz @3,33ms + .staticPriority = TASK_PRIORITY_LOW, + }, +#endif }; diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index b6628d6d99e..ac3505dfe42 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -9,6 +9,7 @@ #include "fc/settings.h" #include "config/general_settings.h" +#include "flight/rpm_filter.h" #include "settings_generated.c" static bool settingGetWord(char *buf, int idx) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8c583229c8d..bf4e5bf2e36 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -81,7 +81,7 @@ tables: values: ["NONE", "GYRO", "AGL", "FLOW_RAW", "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", - "ERPM"] + "ERPM", "RPM_FILTER", "RPM_FREQ"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -871,6 +871,46 @@ groups: min: 0 max: 3 + - name: PG_RPM_FILTER_CONFIG + condition: USE_RPM_FILTER + type: rpmFilterConfig_t + members: + - name: rpm_gyro_filter_enabled + field: gyro_filter_enabled + type: bool + - name: rpm_dterm_filter_enabled + field: dterm_filter_enabled + type: bool + - name: rpm_gyro_harmonics + field: gyro_harmonics + type: uint8_t + min: 1 + max: 3 + - name: rpm_gyro_min_hz + field: gyro_min_hz + type: uint8_t + min: 50 + max: 200 + - name: rpm_gyro_q + field: gyro_q + type: uint16_t + min: 1 + max: 3000 + - name: dterm_gyro_harmonics + field: dterm_harmonics + type: uint8_t + min: 1 + max: 3 + - name: rpm_dterm_min_hz + field: dterm_min_hz + type: uint8_t + min: 50 + max: 200 + - name: rpm_dterm_q + field: dterm_q + type: uint16_t + min: 1 + max: 3000 - name: PG_GPS_CONFIG type: gpsConfig_t condition: USE_GPS diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f0b943d2985..11291381545 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -41,6 +41,7 @@ #include "flight/pid.h" #include "flight/imu.h" #include "flight/mixer.h" +#include "flight/rpm_filter.h" #include "io/gps.h" @@ -696,6 +697,10 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid // Apply D-term notch deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered); +#ifdef USE_RPM_FILTER + deltaFiltered = rpmFilterDtermApply((uint8_t)axis, deltaFiltered); +#endif + // Apply additional lowpass deltaFiltered = dTermLpfFilterApplyFn(&pidState->deltaLpfState, deltaFiltered); diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c new file mode 100644 index 00000000000..e2d9604727b --- /dev/null +++ b/src/main/flight/rpm_filter.c @@ -0,0 +1,232 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "flight/rpm_filter.h" + +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" + +#include "build/debug.h" + +#include "common/axis.h" +#include "common/utils.h" +#include "common/maths.h" +#include "common/filter.h" +#include "flight/mixer.h" +#include "sensors/esc_sensor.h" +#include "fc/config.h" + +#ifdef USE_RPM_FILTER + +#define RPM_TO_HZ 60.0f +#define RPM_FILTER_RPM_LPF_HZ 150 +#define RPM_FILTER_HARMONICS 3 + +PG_REGISTER_WITH_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig, PG_RPM_FILTER_CONFIG, 0); + +PG_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig, + .gyro_filter_enabled = 0, + .dterm_filter_enabled = 0, + .gyro_harmonics = 1, + .gyro_min_hz = 100, + .gyro_q = 500, + .dterm_harmonics = 1, + .dterm_min_hz = 100, + .dterm_q = 500, ); + +typedef struct +{ + float q; + float minHz; + float maxHz; + uint8_t harmonics; + biquadFilter_t filters[XYZ_AXIS_COUNT][MAX_SUPPORTED_MOTORS][RPM_FILTER_HARMONICS]; +} rpmFilterBank_t; + +typedef float (*rpmFilterApplyFnPtr)(rpmFilterBank_t *filter, uint8_t axis, float input); +typedef void (*rpmFilterUpdateFnPtr)(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency); + +static EXTENDED_FASTRAM pt1Filter_t motorFrequencyFilter[MAX_SUPPORTED_MOTORS]; +static EXTENDED_FASTRAM float erpmToHz; +static EXTENDED_FASTRAM rpmFilterBank_t gyroRpmFilters; +static EXTENDED_FASTRAM rpmFilterBank_t dtermRpmFilters; +static EXTENDED_FASTRAM rpmFilterApplyFnPtr rpmGyroApplyFn; +static EXTENDED_FASTRAM rpmFilterApplyFnPtr rpmDtermApplyFn; +static EXTENDED_FASTRAM rpmFilterUpdateFnPtr rpmGyroUpdateFn; +static EXTENDED_FASTRAM rpmFilterUpdateFnPtr rpmDtermUpdateFn; + +float nullRpmFilterApply(rpmFilterBank_t *filter, uint8_t axis, float input) +{ + UNUSED(filter); + UNUSED(axis); + return input; +} + +void nullRpmFilterUpdate(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency) { + UNUSED(filterBank); + UNUSED(motor); + UNUSED(baseFrequency); +} + +float FAST_CODE rpmFilterApply(rpmFilterBank_t *filterBank, uint8_t axis, float input) +{ + float output = input; + + for (uint8_t motor = 0; motor < getMotorCount(); motor++) + { + for (int harmonicIndex = 0; harmonicIndex < filterBank->harmonics; harmonicIndex++) + { + output = biquadFilterApplyDF1( + &filterBank->filters[axis][motor][harmonicIndex], + output + ); + } + } + + return output; +} + +static void rpmFilterInit(rpmFilterBank_t *filter, uint16_t q, uint8_t minHz, uint8_t harmonics) +{ + filter->q = q / 100.0f; + filter->minHz = minHz; + filter->harmonics = harmonics; + /* + * Max frequency has to be lower than Nyquist frequency for looptime + */ + filter->maxHz = 0.48f * 1000000.0f / getLooptime(); + + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) + { + for (int motor = 0; motor < getMotorCount(); motor++) + { + + /* + * Harmonics are indexed from 1 where 1 means base frequency + * C indexes arrays from 0, so we need to shift + */ + for (int harmonicIndex = 0; harmonicIndex < harmonics; harmonicIndex++) + { + biquadFilterInit( + &filter->filters[axis][motor][harmonicIndex], + filter->minHz * (harmonicIndex + 1), + getLooptime(), + filter->q, + FILTER_NOTCH); + } + } + } +} + +void disableRpmFilters(void) { + rpmGyroApplyFn = (rpmFilterApplyFnPtr)nullRpmFilterApply; + rpmDtermApplyFn = (rpmFilterApplyFnPtr)nullRpmFilterApply; +} + +void FAST_CODE NOINLINE rpmFilterUpdate(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency) +{ + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) + { + for (int harmonicIndex = 0; harmonicIndex < filterBank->harmonics; harmonicIndex++) + { + float harmonicFrequency = baseFrequency * (harmonicIndex + 1); + harmonicFrequency = constrainf(harmonicFrequency, filterBank->minHz, filterBank->maxHz); + + biquadFilterUpdate( + &filterBank->filters[axis][motor][harmonicIndex], + harmonicFrequency, + getLooptime(), + filterBank->q, + FILTER_NOTCH); + } + } +} + +void rpmFiltersInit(void) +{ + for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) + { + pt1FilterInit(&motorFrequencyFilter[i], RPM_FILTER_RPM_LPF_HZ, RPM_FILTER_UPDATE_RATE_US * 1e-6f); + } + erpmToHz = ERPM_PER_LSB / (motorConfig()->motorPoleCount / 2) / RPM_TO_HZ; + + rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate; + rpmDtermUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate; + + if (rpmFilterConfig()->gyro_filter_enabled) + { + rpmFilterInit( + &gyroRpmFilters, + rpmFilterConfig()->gyro_q, + rpmFilterConfig()->gyro_min_hz, + rpmFilterConfig()->gyro_harmonics); + rpmGyroApplyFn = (rpmFilterApplyFnPtr)rpmFilterApply; + rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)rpmFilterUpdate; + } + + if (rpmFilterConfig()->dterm_filter_enabled) + { + rpmFilterInit( + &dtermRpmFilters, + rpmFilterConfig()->dterm_q, + rpmFilterConfig()->dterm_min_hz, + rpmFilterConfig()->dterm_harmonics); + rpmDtermApplyFn = (rpmFilterApplyFnPtr)rpmFilterApply; + rpmDtermUpdateFn = (rpmFilterUpdateFnPtr)rpmFilterUpdate; + } +} + +void FAST_CODE NOINLINE rpmFilterUpdateTask(timeUs_t currentTimeUs) +{ + UNUSED(currentTimeUs); + + uint8_t motorCount = getMotorCount(); + /* + * For each motor, read ERPM, filter it and update motor frequency + */ + for (uint8_t i = 0; i < motorCount; i++) + { + const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry + const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], escState->rpm * erpmToHz); //Filter motor frequency + + if (i < 4) { + DEBUG_SET(DEBUG_RPM_FREQ, i, (int)baseFrequency); + } + + rpmGyroUpdateFn(&gyroRpmFilters, i, baseFrequency); + rpmDtermUpdateFn(&dtermRpmFilters, i, baseFrequency); + } +} + +float FAST_CODE rpmFilterGyroApply(uint8_t axis, float input) +{ + return rpmGyroApplyFn(&gyroRpmFilters, axis, input); +} + +float FAST_CODE rpmFilterDtermApply(uint8_t axis, float input) +{ + return rpmDtermApplyFn(&dtermRpmFilters, axis, input); +} + +#endif \ No newline at end of file diff --git a/src/main/flight/rpm_filter.h b/src/main/flight/rpm_filter.h new file mode 100644 index 00000000000..29f825152c5 --- /dev/null +++ b/src/main/flight/rpm_filter.h @@ -0,0 +1,53 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include "config/parameter_group.h" +#include "common/time.h" + +typedef struct rpmFilterConfig_s { + uint8_t gyro_filter_enabled; + uint8_t dterm_filter_enabled; + + uint8_t gyro_harmonics; + uint8_t gyro_min_hz; + uint16_t gyro_q; + + uint8_t dterm_harmonics; + uint8_t dterm_min_hz; + uint16_t dterm_q; + +} rpmFilterConfig_t; + +PG_DECLARE(rpmFilterConfig_t, rpmFilterConfig); + +#define RPM_FILTER_UPDATE_RATE_HZ 500 +#define RPM_FILTER_UPDATE_RATE_US (1000000.0f / RPM_FILTER_UPDATE_RATE_HZ) + +void disableRpmFilters(void); +void rpmFiltersInit(void); +void rpmFilterUpdateTask(timeUs_t currentTimeUs); +float rpmFilterGyroApply(uint8_t axis, float input); +float rpmFilterDtermApply(uint8_t axis, float input); \ No newline at end of file diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 5cf996f02e4..b9cf88bd212 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -115,6 +115,9 @@ typedef enum { #endif #ifdef USE_GLOBAL_FUNCTIONS TASK_GLOBAL_FUNCTIONS, +#endif +#ifdef USE_RPM_FILTER + TASK_RPM_FILTER, #endif /* Count of real tasks */ TASK_COUNT, diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 82180c43bff..97437315815 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -130,6 +130,15 @@ static bool escSensorDecodeFrame(void) return ESC_SENSOR_FRAME_PENDING; } +uint32_t FAST_CODE computeRpm(int16_t erpm) { + return lrintf((float)erpm * ERPM_PER_LSB / (motorConfig()->motorPoleCount / 2)); +} + +escSensorData_t NOINLINE * getEscTelemetry(uint8_t esc) +{ + return &escSensorData[esc]; +} + escSensorData_t * escSensorGetData(void) { if (!escSensorPort) { @@ -160,7 +169,7 @@ escSensorData_t * escSensorGetData(void) if (usedEscSensorCount) { escSensorDataCombined.current = (uint32_t)escSensorDataCombined.current * getMotorCount() / usedEscSensorCount + escSensorConfig()->currentOffset; escSensorDataCombined.voltage = (uint32_t)escSensorDataCombined.voltage / usedEscSensorCount; - escSensorDataCombined.rpm = lrintf(((float)escSensorDataCombined.rpm / usedEscSensorCount) * 100.0f / (motorConfig()->motorPoleCount / 2)); + escSensorDataCombined.rpm = computeRpm((float)escSensorDataCombined.rpm / usedEscSensorCount); } else { escSensorDataCombined.dataAge = ESC_DATA_INVALID; diff --git a/src/main/sensors/esc_sensor.h b/src/main/sensors/esc_sensor.h index e8aecf78b24..1e10d834b4d 100644 --- a/src/main/sensors/esc_sensor.h +++ b/src/main/sensors/esc_sensor.h @@ -40,7 +40,10 @@ PG_DECLARE(escSensorConfig_t, escSensorConfig); #define ESC_DATA_MAX_AGE 10 #define ESC_DATA_INVALID 255 +#define ERPM_PER_LSB 100.0f bool escSensorInitialize(void); void escSensorUpdate(timeUs_t currentTimeUs); escSensorData_t * escSensorGetData(void); +escSensorData_t * getEscTelemetry(uint8_t esc); +uint32_t computeRpm(int16_t erpm); diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 1d76a125d6a..d17e38781aa 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -68,6 +68,7 @@ #include "sensors/sensors.h" #include "flight/gyroanalyse.h" +#include "flight/rpm_filter.h" #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" @@ -464,6 +465,12 @@ void FAST_CODE NOINLINE gyroUpdate() DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf)); +#ifdef USE_RPM_FILTER + DEBUG_SET(DEBUG_RPM_FILTER, axis, gyroADCf); + gyroADCf = rpmFilterGyroApply(axis, gyroADCf); + DEBUG_SET(DEBUG_RPM_FILTER, axis + 3, gyroADCf); +#endif + gyroADCf = gyroFilterStage2ApplyFn(stage2Filter[axis], gyroADCf); gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf); gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf); @@ -484,6 +491,7 @@ void FAST_CODE NOINLINE gyroUpdate() gyroDataAnalyse(&gyroAnalyseState, notchFilterDyn, notchFilterDyn2); } #endif + } bool gyroReadTemperature(void) diff --git a/src/main/target/COLIBRI_RACE/target.mk b/src/main/target/COLIBRI_RACE/target.mk_ similarity index 100% rename from src/main/target/COLIBRI_RACE/target.mk rename to src/main/target/COLIBRI_RACE/target.mk_ diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index ce093463d23..28169a3ab1c 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -198,4 +198,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT #define USE_SERIALSHOT -#define USE_ESC_SENSOR +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index f9fc0a6227d..11270303791 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -154,5 +154,3 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) - -#undef USE_PWM_SERVO_DRIVER \ No newline at end of file diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h index 465a829b4f6..b8a29fc50d3 100755 --- a/src/main/target/SPRACINGF3NEO/target.h +++ b/src/main/target/SPRACINGF3NEO/target.h @@ -113,7 +113,6 @@ #undef USE_VTX_FFPV #undef USE_VTX_SMARTAUDIO // Disabled due to flash size #undef USE_VTX_TRAMP // Disabled due to flash size -#undef USE_PWM_SERVO_DRIVER // Disabled due to RAM size #undef USE_PITOT // Disabled due to RAM size #undef USE_PITOT_ADC // Disabled due to RAM size diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 32fed24a5e0..d90d85a5b8d 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -40,6 +40,10 @@ #define USE_CANVAS #endif +#ifdef USE_ESC_SENSOR + #define USE_RPM_FILTER +#endif + #ifdef USE_ITCM_RAM #define FAST_CODE __attribute__((section(".tcm_code"))) #define NOINLINE __NOINLINE @@ -54,6 +58,7 @@ #undef USE_SERIALRX_SUMH #undef USE_SERIALRX_XBUS #undef USE_SERIALRX_JETIEXBUS +#undef USE_PWM_SERVO_DRIVER #endif #if defined(SIMULATOR_BUILD) || defined(UNIT_TEST) From 753eb4c162aadac8653f68da89a05d39dacf58b2 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 8 Dec 2019 22:18:19 +0100 Subject: [PATCH 036/110] Fix PID bank selection --- src/main/flight/pid.c | 9 ++++++++- src/main/flight/pid.h | 6 ++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 11291381545..9d5d09fa7e8 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1053,7 +1053,7 @@ void pidInit(void) #endif if (pidProfile()->pidControllerType == PID_TYPE_AUTO) { - if (STATE(FIXED_WING)) { + if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { usedPidControllerType = PID_TYPE_PIFF; } else { usedPidControllerType = PID_TYPE_PID; @@ -1076,3 +1076,10 @@ void pidInit(void) pidControllerApplyFn = nullRateController; } } + +const pidBank_t FAST_CODE NOINLINE * pidBank(void) { + return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; +} +pidBank_t FAST_CODE NOINLINE * pidBankMutable(void) { + return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; +} diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 41f30dbf2d2..4cf0f1110ce 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -157,10 +157,8 @@ typedef struct pidAutotuneConfig_s { PG_DECLARE_PROFILE(pidProfile_t, pidProfile); PG_DECLARE(pidAutotuneConfig_t, pidAutotuneConfig); -static uint8_t usedPidControllerType; - -static inline const pidBank_t * pidBank(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } -static inline pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } +const pidBank_t * pidBank(void); +pidBank_t * pidBankMutable(void); extern int16_t axisPID[]; extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[]; From b9311541e414d3c4410cd7de16eccce4174e12e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 27 Oct 2019 18:31:45 +0000 Subject: [PATCH 037/110] [MAKE] Split makefiles, add support for OpenOCD and GDB - Move make/local.mk to the top of the Makefile, so it can set any variables - Move target and group definitions to make/targets.mk - Move settings related rules to make/settings.mk - Move build-stamp rules to make/stamp.mk - Define STM32 flash offset in a variable in make/mcu/STM32.mk - Add make/openocd.mk with openocd-run and openocd-flash targets - Add make/gdb.mk with gdb-openocd target --- Makefile | 151 ++++++---------------------------------------- make/gdb.mk | 9 +++ make/mcu/STM32.mk | 1 + make/openocd.mk | 27 +++++++++ make/settings.mk | 26 ++++++++ make/stamp.mk | 7 +++ make/targets.mk | 96 +++++++++++++++++++++++++++++ 7 files changed, 184 insertions(+), 133 deletions(-) create mode 100644 make/gdb.mk create mode 100644 make/mcu/STM32.mk create mode 100644 make/openocd.mk create mode 100644 make/settings.mk create mode 100644 make/stamp.mk create mode 100644 make/targets.mk diff --git a/Makefile b/Makefile index 269c6b78326..5aa9ddd88e0 100644 --- a/Makefile +++ b/Makefile @@ -11,6 +11,11 @@ # ############################################################################### +# Root directory +ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) + +# developer preferences, edit these at will, they'll be gitignored +-include $(ROOT)/make/local.mk # Things that the user might override on the commandline # @@ -60,7 +65,6 @@ endif FORKNAME = inav # Working directories -ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) SRC_DIR := $(ROOT)/src/main OBJECT_DIR := $(ROOT)/obj/main BIN_DIR := $(ROOT)/obj @@ -72,9 +76,6 @@ LINKER_DIR := $(ROOT)/src/main/target/link # import macros common to all supported build systems include $(ROOT)/make/system-id.mk -# developer preferences, edit these at will, they'll be gitignored --include $(ROOT)/make/local.mk - # default xtal value for F4 targets HSE_VALUE = 8000000 MHZ_VALUE ?= @@ -82,59 +83,7 @@ MHZ_VALUE ?= # used for turning on features like VCP and SDCARD FEATURES = -ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) - -VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) -VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) -VALID_TARGETS := $(sort $(VALID_TARGETS)) - -CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) -TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) -STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) ) - -ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) -BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) --include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk -else -BASE_TARGET := $(TARGET) -endif - -# silently ignore if the file is not present. Allows for target specific. --include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk - -F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS) -F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) - -ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) -$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) -endif - -ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) -$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?) -endif - -ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -TARGET_MCU := STM32F3 -else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) -TARGET_MCU := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS))) -TARGET_MCU := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F1_TARGETS))) -TARGET_MCU := STM32F1 -else -$(error Unknown target MCU specified.) -endif - -GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD -GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX -GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 -GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX -GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD -GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 -GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 -GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) +include $(ROOT)/make/targets.mk REVISION = $(shell git rev-parse --short HEAD) @@ -158,6 +107,7 @@ VPATH := $(VPATH):$(ROOT)/make CSOURCES := $(shell find $(SRC_DIR) -name '*.c') # start specific includes +include $(ROOT)/make/mcu/STM32.mk include $(ROOT)/make/mcu/$(TARGET_MCU).mk # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. @@ -307,41 +257,15 @@ TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map CLEAN_ARTIFACTS := $(TARGET_BIN) CLEAN_ARTIFACTS += $(TARGET_HEX) -CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) +CLEAN_ARTIFACTS += $(TARGET_ELF) +CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP) + +include $(ROOT)/make/stamp.mk +include $(ROOT)/make/settings.mk # Make sure build date and revision is updated on every incremental build $(TARGET_OBJ_DIR)/build/version.o : $(TARGET_SRC) -# Settings generator -.PHONY: .FORCE settings clean-settings -UTILS_DIR = $(ROOT)/src/utils -SETTINGS_GENERATOR = $(UTILS_DIR)/settings.rb -BUILD_STAMP = $(UTILS_DIR)/build_stamp.rb -STAMP = $(TARGET_OBJ_DIR)/build.stamp - -GENERATED_SETTINGS = $(TARGET_OBJ_DIR)/settings_generated.h $(TARGET_OBJ_DIR)/settings_generated.c -SETTINGS_FILE = $(SRC_DIR)/fc/settings.yaml -GENERATED_FILES = $(GENERATED_SETTINGS) -$(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP) - -# Make sure the generated files are in the include path -CFLAGS += -I$(TARGET_OBJ_DIR) - -$(STAMP): .FORCE - $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP) - -# Use a pattern rule, since they're different than normal rules. -# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples -%generated.h %generated.c: - $(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)" - $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR) - -settings-json: - $(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json - -clean-settings: - $(V1) $(RM) $(GENERATED_SETTINGS) - # CFLAGS used for ASM generation. These can't include the LTO related options # since they prevent proper ASM generation. Since $(LTO_FLAGS) includes the # optization level, we have to add it back. -g is required to make interleaved @@ -352,7 +276,7 @@ ASM_CFLAGS=-g $(OPTIMZE) $(filter-out $(LTO_FLAGS) -save-temps=obj, $(CFLAGS)) # It would be nice to compute these lists, but that seems to be just beyond make. $(TARGET_HEX): $(TARGET_ELF) - $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + $(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@ $(TARGET_BIN): $(TARGET_ELF) $(V0) $(OBJCOPY) -O binary $< $@ @@ -395,33 +319,6 @@ $(TOOLS_DIR): ## all : Build all valid targets all: $(VALID_TARGETS) -## targets-group-1 : build some targets -targets-group-1: $(GROUP_1_TARGETS) - -## targets-group-2 : build some targets -targets-group-2: $(GROUP_2_TARGETS) - -## targets-group-3 : build some targets -targets-group-3: $(GROUP_3_TARGETS) - -## targets-group-4 : build some targets -targets-group-4: $(GROUP_4_TARGETS) - -## targets-group-5 : build some targets -targets-group-5: $(GROUP_5_TARGETS) - -## targets-group-6 : build some targets -targets-group-6: $(GROUP_6_TARGETS) - -## targets-group-7 : build some targets -targets-group-7: $(GROUP_7_TARGETS) - -## targets-group-8 : build some targets -targets-group-8: $(GROUP_8_TARGETS) - -## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3) -targets-group-rest: $(GROUP_OTHER_TARGETS) - ## targets-group-rest: build targets specified in release-targets list release: $(RELEASE_TARGETS) @@ -469,7 +366,7 @@ $(STFLASH_TARGETS) : ## st-flash : flash firmware (.bin) onto flight controller st-flash: $(TARGET_BIN) - $(V0) st-flash --reset write $< 0x08000000 + $(V0) st-flash --reset write $< $(FLASH_ORIGIN) binary: $(TARGET_BIN) hex: $(TARGET_HEX) @@ -502,22 +399,6 @@ help: Makefile $(V0) @echo "" $(V0) @sed -n 's/^## //p' $< -## targets : print a list of all valid target platforms (for consumption by scripts) -targets: - $(V0) @echo "Valid targets: $(VALID_TARGETS)" - $(V0) @echo "Target: $(TARGET)" - $(V0) @echo "Base target: $(BASE_TARGET)" - $(V0) @echo "targets-group-1: $(GROUP_1_TARGETS)" - $(V0) @echo "targets-group-2: $(GROUP_2_TARGETS)" - $(V0) @echo "targets-group-3: $(GROUP_3_TARGETS)" - $(V0) @echo "targets-group-4: $(GROUP_4_TARGETS)" - $(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)" - $(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)" - $(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)" - $(V0) @echo "targets-group-7: $(GROUP_8_TARGETS)" - $(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)" - $(V0) @echo "Release targets: $(RELEASE_TARGETS)" - ## test : run the cleanflight test suite test: $(V0) cd src/test && $(MAKE) test @@ -530,3 +411,7 @@ $(TARGET_OBJS) : Makefile | $(GENERATED_FILES) $(STAMP) # include auto-generated dependencies -include $(TARGET_DEPS) + +# Developer tools +include $(ROOT)/make/openocd.mk +include $(ROOT)/make/gdb.mk diff --git a/make/gdb.mk b/make/gdb.mk new file mode 100644 index 00000000000..f7dc6f4c42f --- /dev/null +++ b/make/gdb.mk @@ -0,0 +1,9 @@ +GDB ?= $(ARM_SDK_PREFIX)gdb +GDB_OPENOCD_REMOTE ?= localhost:3333 + +GDB_OPENOCD_INIT_CMDS = -ex "arm semihosting enable" -ex "monitor reset halt" + +gdb-openocd: $(TARGET_ELF) + (nc -z $(subst :, ,$(GDB_OPENOCD_REMOTE)) 2> /dev/null && \ + $(GDB) $< -ex "target remote $(GDB_OPENOCD_REMOTE)" $(GDB_OPENOCD_RESET)) || \ + $(GDB) $< -ex "target remote | $(OPENOCD_CMDLINE) -c \"gdb_port pipe;\"" $(GDB_OPENOCD_RESET) diff --git a/make/mcu/STM32.mk b/make/mcu/STM32.mk new file mode 100644 index 00000000000..2c1636561ef --- /dev/null +++ b/make/mcu/STM32.mk @@ -0,0 +1 @@ +FLASH_ORIGIN ?= 0x08000000 diff --git a/make/openocd.mk b/make/openocd.mk new file mode 100644 index 00000000000..ec97939e856 --- /dev/null +++ b/make/openocd.mk @@ -0,0 +1,27 @@ +.PHONY: openocd + +OPENOCD_CMD ?= openocd +OPENOCD_INTERFACE ?= stlink-v2 + +ifeq ($(TARGET_MCU),STM32F1) +OPENOCD_TARGET ?= stm32f1x +else ifeq ($(TARGET_MCU),STM32F3) +OPENOCD_TARGET ?= stm32f3x +else ifeq ($(TARGET_MCU),STM32F4) +OPENOCD_TARGET ?= stm32f4x +else ifeq ($(TARGET_MCU),STM32F7) +OPENOCD_TARGET ?= stm32f7x +endif + +ifeq ($(OPENOCD_TARGET),) +$(warning Unknown OPENOCD_TARGET) +endif + +OPENOCD_CMDLINE := $(OPENOCD_CMD) -f interface/$(OPENOCD_INTERFACE).cfg -f target/$(OPENOCD_TARGET).cfg + +openocd-run: + $(OPENOCD_CMDLINE) + +openocd-flash: $(TARGET_ELF) + (echo "halt; program $(realpath $<) verify reset" | nc -4 localhost 4444 2>/dev/null) || \ + $(OPENOCD_CMDLINE) -c "program $< verify reset exit" diff --git a/make/settings.mk b/make/settings.mk new file mode 100644 index 00000000000..c73ff2e690a --- /dev/null +++ b/make/settings.mk @@ -0,0 +1,26 @@ +# Settings generator +.PHONY: settings clean-settings +UTILS_DIR = $(ROOT)/src/utils +SETTINGS_GENERATOR = $(UTILS_DIR)/settings.rb + +GENERATED_SETTINGS = $(TARGET_OBJ_DIR)/settings_generated.h $(TARGET_OBJ_DIR)/settings_generated.c +SETTINGS_FILE = $(SRC_DIR)/fc/settings.yaml +GENERATED_FILES = $(GENERATED_SETTINGS) +$(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP) + +CLEAN_ARTIFACTS += $(GENERATED_SETTINGS) + +# Make sure the generated files are in the include path +CFLAGS += -I$(TARGET_OBJ_DIR) + +# Use a pattern rule, since they're different than normal rules. +# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples +%generated.h %generated.c: + $(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)" + $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR) + +settings-json: + $(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json + +clean-settings: + $(V1) $(RM) $(GENERATED_SETTINGS) diff --git a/make/stamp.mk b/make/stamp.mk new file mode 100644 index 00000000000..f68f68d2ae0 --- /dev/null +++ b/make/stamp.mk @@ -0,0 +1,7 @@ +.PHONY: .FORCE + +BUILD_STAMP = $(UTILS_DIR)/build_stamp.rb +STAMP = $(TARGET_OBJ_DIR)/build.stamp + +$(STAMP): .FORCE + $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP) diff --git a/make/targets.mk b/make/targets.mk new file mode 100644 index 00000000000..76b46722c98 --- /dev/null +++ b/make/targets.mk @@ -0,0 +1,96 @@ +ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) + +VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) +VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) +VALID_TARGETS := $(sort $(VALID_TARGETS)) + +CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) +TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) +STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) ) + +ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) +BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) +-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk +else +BASE_TARGET := $(TARGET) +endif + +# silently ignore if the file is not present. Allows for target specific. +-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk + +F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS) +F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) + +ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) +$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) +endif + +ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) +$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?) +endif + +ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +TARGET_MCU := STM32F3 +else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) +TARGET_MCU := STM32F4 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS))) +TARGET_MCU := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F1_TARGETS))) +TARGET_MCU := STM32F1 +else +$(error Unknown target MCU specified.) +endif + +GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI KISSFC FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD +GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX +GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 +GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX +GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD +GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 +GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO +GROUP_8_TARGETS := MATEKF765 +GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) + +## targets-group-1 : build some targets +targets-group-1: $(GROUP_1_TARGETS) + +## targets-group-2 : build some targets +targets-group-2: $(GROUP_2_TARGETS) + +## targets-group-3 : build some targets +targets-group-3: $(GROUP_3_TARGETS) + +## targets-group-4 : build some targets +targets-group-4: $(GROUP_4_TARGETS) + +## targets-group-5 : build some targets +targets-group-5: $(GROUP_5_TARGETS) + +## targets-group-6 : build some targets +targets-group-6: $(GROUP_6_TARGETS) + +## targets-group-7 : build some targets +targets-group-7: $(GROUP_7_TARGETS) + +## targets-group-8 : build some targets +targets-group-8: $(GROUP_8_TARGETS) + +## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3) +targets-group-rest: $(GROUP_OTHER_TARGETS) + +## targets : print a list of all valid target platforms (for consumption by scripts) +targets: + $(V0) @echo "Valid targets: $(VALID_TARGETS)" + $(V0) @echo "Target: $(TARGET)" + $(V0) @echo "Base target: $(BASE_TARGET)" + $(V0) @echo "targets-group-1: $(GROUP_1_TARGETS)" + $(V0) @echo "targets-group-2: $(GROUP_2_TARGETS)" + $(V0) @echo "targets-group-3: $(GROUP_3_TARGETS)" + $(V0) @echo "targets-group-4: $(GROUP_4_TARGETS)" + $(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)" + $(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)" + $(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)" + $(V0) @echo "targets-group-8: $(GROUP_8_TARGETS)" + $(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)" + $(V0) @echo "Release targets: $(RELEASE_TARGETS)" From 987c7bb73e9a935194ac0947b2e4749574f345f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 27 Oct 2019 18:35:05 +0000 Subject: [PATCH 038/110] [MAKE/LOG] Add support for semihosting Semihosting allows printing debug messages via SWD --- Makefile | 12 ++++++++++++ make/gdb.mk | 12 +++++++++--- src/main/common/log.c | 16 ++++++++++++++++ 3 files changed, 37 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index 5aa9ddd88e0..407a482a521 100644 --- a/Makefile +++ b/Makefile @@ -29,6 +29,8 @@ OPTIONS ?= # Debugger optons, must be empty or GDB DEBUG ?= +SEMIHOSTING ?= + # Build suffix BUILD_SUFFIX ?= @@ -180,6 +182,14 @@ OPTIMIZE = -Os LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) endif +ifneq ($(SEMIHOSTING),) +SEMIHOSTING_CFLAGS = -DSEMIHOSTING +SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon +else +SEMIHOSTING_CFLAGS = +SEMIHOSTING_LDFLAGS = +endif + DEBUG_FLAGS = -ggdb3 -DDEBUG CFLAGS += $(ARCH_FLAGS) \ @@ -187,6 +197,7 @@ CFLAGS += $(ARCH_FLAGS) \ $(addprefix -D,$(OPTIONS)) \ $(addprefix -I,$(INCLUDE_DIRS)) \ $(DEBUG_FLAGS) \ + $(SEMIHOSTING_CFLAGS) \ -std=gnu99 \ -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ -Wstrict-prototypes \ @@ -217,6 +228,7 @@ LDFLAGS = -lm \ $(ARCH_FLAGS) \ $(LTO_FLAGS) \ $(DEBUG_FLAGS) \ + $(SEMIHOSTING_LDFLAGS) \ -static \ -Wl,-gc-sections,-Map,$(TARGET_MAP) \ -Wl,-L$(LINKER_DIR) \ diff --git a/make/gdb.mk b/make/gdb.mk index f7dc6f4c42f..cbf228a1b89 100644 --- a/make/gdb.mk +++ b/make/gdb.mk @@ -1,9 +1,15 @@ GDB ?= $(ARM_SDK_PREFIX)gdb GDB_OPENOCD_REMOTE ?= localhost:3333 -GDB_OPENOCD_INIT_CMDS = -ex "arm semihosting enable" -ex "monitor reset halt" +GDB_OPENOCD_INIT_CMDS ?= -ex "monitor reset halt" +ifneq ($(LOAD),) +GDB_OPENOCD_INIT_CMDS += -ex load +endif +ifneq ($(SEMIHOSTING),) +GDB_OPENOCD_INIT_CMDS += -ex "monitor arm semihosting enable" +endif gdb-openocd: $(TARGET_ELF) (nc -z $(subst :, ,$(GDB_OPENOCD_REMOTE)) 2> /dev/null && \ - $(GDB) $< -ex "target remote $(GDB_OPENOCD_REMOTE)" $(GDB_OPENOCD_RESET)) || \ - $(GDB) $< -ex "target remote | $(OPENOCD_CMDLINE) -c \"gdb_port pipe;\"" $(GDB_OPENOCD_RESET) + $(GDB) $< -ex "target remote $(GDB_OPENOCD_REMOTE)" $(GDB_OPENOCD_INIT_CMDS)) || \ + $(GDB) $< -ex "target remote | $(OPENOCD_CMDLINE) -c \"gdb_port pipe;\"" $(GDB_OPENOCD_INIT_CMDS) diff --git a/src/main/common/log.c b/src/main/common/log.c index cc13c2a786c..07eda4c7394 100644 --- a/src/main/common/log.c +++ b/src/main/common/log.c @@ -20,6 +20,10 @@ #include #include +#if defined(SEMIHOSTING) +#include +#endif + #include "build/version.h" #include "drivers/serial.h" @@ -103,6 +107,18 @@ static void logPutcp(void *p, char ch) static void logPrint(const char *buf, size_t size) { +#if defined(SEMIHOSTING) + static bool semihostingInitialized = false; + extern void initialise_monitor_handles(void); + + if (!semihostingInitialized) { + initialise_monitor_handles(); + semihostingInitialized = true; + } + for (size_t ii = 0; ii < size; ii++) { + fputc(buf[ii], stdout); + } +#endif if (logPort) { // Send data via UART (if configured & connected - a safeguard against zombie VCP) if (serialIsConnected(logPort)) { From 27ae5a3ef9efa3b64a57301eb0cc0965eb5d2b7f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 27 Oct 2019 20:30:39 +0000 Subject: [PATCH 039/110] [MAKE] Add elf target to the Makefile Builds the .elf for the current target --- Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/Makefile b/Makefile index 407a482a521..ae41d6b1b56 100644 --- a/Makefile +++ b/Makefile @@ -380,6 +380,7 @@ $(STFLASH_TARGETS) : st-flash: $(TARGET_BIN) $(V0) st-flash --reset write $< $(FLASH_ORIGIN) +elf: $(TARGET_ELF) binary: $(TARGET_BIN) hex: $(TARGET_HEX) From 48b921be0ecd555d9b70c22136a456a0b6022d1c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 4 Nov 2019 16:19:09 +0000 Subject: [PATCH 040/110] [DOC] Document hardware debugging procedure with stlink, openocd and gdb --- docs/development/Hardware Debugging.md | 206 +++++++++++------- .../OLIMEX-ARM-JTAG-ADAPTER-2144328-40.jpg | Bin 4923 -> 0 bytes .../assets/hardware/THAOYU-USB-MiniJTAG.jpg | Bin 73488 -> 0 bytes .../assets/hardware/j-link-edu.jpg | Bin 16001 -> 0 bytes make/gdb.mk | 9 +- make/openocd.mk | 54 +++-- 6 files changed, 172 insertions(+), 97 deletions(-) delete mode 100644 docs/development/assets/hardware/OLIMEX-ARM-JTAG-ADAPTER-2144328-40.jpg delete mode 100644 docs/development/assets/hardware/THAOYU-USB-MiniJTAG.jpg delete mode 100644 docs/development/assets/hardware/j-link-edu.jpg diff --git a/docs/development/Hardware Debugging.md b/docs/development/Hardware Debugging.md index 7c0002306a0..0bf9a2059df 100644 --- a/docs/development/Hardware Debugging.md +++ b/docs/development/Hardware Debugging.md @@ -1,106 +1,160 @@ -# Hardware debugging +# Hardware Debugging -The code can be compiled with debugging information, you can then upload a debug version to a board via a JLink/St-Link debug adapter and step through the code in your IDE. +Hardware debugging allows debugging the firmware with GDB, including most of its +features that you can find while debugging software for a computer like setting +breakpoins or printing variables or stepping through the code. -More information about the necessary hardware and setting up the eclipse IDE can be found [here](Hardware Debugging in Eclipse.md) +Additionally, firmware can also be flashed directly either from the IDE or from GDB, +significanly reducing the time required for the compile/flash/test cycle. -A guide for visual studio can be found here: -http://visualgdb.com/tutorials/arm/st-link/ +## Required Hardware -This video is also helpful in understanding the proces: -https://www.youtube.com/watch?v=kjvqySyNw20 +Although more complex and expensive solutions exists, an STLink V2 clone will let you +use all the features of hardware debugging. They can be purchased on any of the typical +Chinese sites. -## Hardware +[ST Link V2 Clone](https://inavflight.com/shop/s/bg/1177014) +[Original ST Link V2](https://inavflight.com/shop/s/bg/1099119) -Various debugging hardware solutions exist, the Segger J-Link clones are cheap and are known to work on Windows. +Additionally, most nucleo boards from ST come with a brekable part that contains an +STLink V2.1 or V3. These can also be used to debug an FC, but can be more difficult to +source. -### J-Link devices +To connect it a flight controller, you need to locate the SWDIO and SWCLK pins from the +MCU. These correspond to PA13 (SWDIO) and PA14 (SWCLK). Be aware that not all manufacturers +break out these pins, but a lot of them put them in small pads available somewhere. +Connect SWDIO, SWCLK and GND from the FC to pins with the FC -Segger make excellent debuggers and debug software. +TODO: Add pictures of several FCs with SWDIO and SWCLK highlighted. -The Segger J-Link GDB server can be obtained from here. +## Required software -http://www.segger.com/jlink-software.html +Besides an ARM toolchain, [OpenOCD](http://openocd.org) is required. Note that at the +time of this writing, OpenOCD hasn't had a release in almost 3 years, so you might +need to look for unofficial releases or compile from source. -#### Segger J-Link EDU EDU version, for hobbyists and educational use. +[stlink](https://github.com/texane/stlink), while not strictly required, can be handy +for quickly testing the SWD connection or flashing or erasing. To avoid ambiguities +between the hardware and the software, the former will be referred as `ST Link` while +we'll use `stlink` for the latter. -![Segger J-Link EDU](assets/hardware/j-link-edu.jpg) +Please, follow the installation instructions for your operating system. -https://www.segger.com/j-link-edu.html +### Windows -#### USB-MiniJTAG J-Link JTAG/SWD Debugger/Emulator +Install the Windows Subsystem for Linux, then follow the Linux instructions. -http://www.hotmcu.com/usbminijtag-jlink-jtagswd-debuggeremula%E2%80%8Btor-p-29.html?cPath=3_25&zenid=fdefvpnod186umrhsek225dc10 +### macOS -![THAOYU USB-MiniJTAG](assets/hardware/THAOYU-USB-MiniJTAG.jpg) +Install [Homebrew](https://brew.sh) (a package manager) first. -##### ARM-JTAG-20-10 adapter +To install OpenOCD type `brew install open-ocd --HEAD` in a terminal. Note the `--HEAD` +command line switch. -https://www.olimex.com/Products/ARM/JTAG/ARM-JTAG-20-10/ -http://uk.farnell.com/jsp/search/productdetail.jsp?sku=2144328 +For stlink, use `brew install stlink`. -![OLIMEX ARM JTAG ADAPTER](assets/hardware/OLIMEX-ARM-JTAG-ADAPTER-2144328-40.jpg) +### Linux -#### CJMCU-STM32 Singlechip Development Board Jlink Downloader Jlink ARM Programmer +Install [Homebrew for Linux](https://docs.brew.sh/Homebrew-on-Linux), since versions +provided by your distro's package manager might be out of date. Homebrew can cohexist +with your existing package manager without any problems. -![CJMCU-STM32 Jlink ARM Programmer Front](assets/hardware/cjmcu-jlink-front.jpg) +Then, follow the same instructions for installing OpenOCD and stlink for macOS. -![CJMCU-STM32 Jlink ARM Programmer Back](assets/hardware/cjmcu-jlink-back.jpg) +## Hardware setup -http://www.goodluckbuy.com/cjmcu-stm32-singlechip-development-board-jlink-downloader-jlink-arm-programmer.html +Connect SWDIO and SWCLK from the FC to pins with the same label on the ST Link. You must +also connect one of the GND from FC to any of the GND pins to the ST Link. Note the +following caveats: +- There are several ST Link clone types with different pinouts. Pay attention to the pin +labels. +- In some ST Link clones, some GND pins are actually floating and not connected to +- anything. Use a multimeter to check the GND pins and use any of the valid ones. +- Even if you're powering everything from the same computer, make sure to directly connect +the grounds from the FC to the ST Link. Some FC/stlink combinations have a 0.1-0.2V +difference between their grounds and if you don't connect them, stlink won't work. -### STLink V2 devices +The FC can be powered by any power source that it supports (battery, USB, etc...), just +make sure to not connect power from the ST Link (the pins labelled as 3.3V and 5V) to the +FC if something else is powering it. -STLink V2 devices can be used too, via OpenOCD. +Once you're wired everything, test the connections with a DMM before applying power. Then +power both the FC and the stlink (the order doesn't matter) and run `st-info --probe` +You should see something like: -#### CEPark STLink V2 - -![CEPark STLink V2](assets/hardware/cepark-stlink-v2-front.jpg) - -http://www.goodluckbuy.com/cepark-stlink-st-link-v2-emulator-programmer-stm8-stm32-downloader.html +``` +Found 1 stlink programmers + serial: 0d0d09002a12354d314b4e00 +openocd: "\x0d\x0d\x09\x00\x2a\x12\x35\x4d\x31\x4b\x4e\x00" + flash: 524288 (pagesize: 16384) + sram: 131072 + chipid: 0x0431 + descr: F4 device (low power) - stm32f411re +``` ## Compilation options -use `DEBUG=GDB` make argument. - -You may find that if you compile all the files with debug information on that the program is too big to fit on the target device. If this happens you have some options: - -* Compile all files without debug information (`make clean`, `make ...`), then re-save or `touch` the files you want to be able to step though and then run `make DEBUG=GDB`. This will then re-compile the files you're interested in debugging with debugging symbols and you will get a smaller binary file which should then fit on the device. -* You could use a development board such as an EUSTM32F103RB, development boards often have more flash rom. - -## OSX - -### Install OpenOCD via Brew - -ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" - -brew install openocd - -### GDB debug server - -#### J-Link - -##### Windows - -Run the Launch the J-Link GDB Server program and configure using UI. - -#### OpenOCD - -##### Windows - -STM32F103 targets - - "C:\Program Files (x86)\UTILS\openocd-0.8.0\bin-x64\openocd-x64-0.8.0.exe" -f interface/stlink-v2.cfg -f target/stm32f1x_stlink.cfg - -STM32F30x targets - - "C:\Program Files (x86)\UTILS\openocd-0.8.0\bin-x64\openocd-x64-0.8.0.exe" -f scripts\board\stm32f3discovery.cfg - -##### OSX/Linux - -STM32F30x targets - - openocd -f /usr/share/openocd/scripts/board/stm32vldiscovery.cfg - - +INAV is compiled with debug symbols by default, since they're only stored in the locally +generated `.elf` file and they never use flash space in the target. However, some +optimizations like inlining and LTO might rearrange some sections of the code enough +to interfere with debugging. All compile time optimizations can be disabled by +using `DEBUG=GDB` when calling `make`. + +You may find that if you compile all the files without optimizations the program might +too big to fit on the target device. In that case, one of the possible solutions is +compiling all files with optimization (`make clean`, `make ...`) first, then re-save +or `touch` the files you want to be able to step though and then run `make DEBUG=GDB`. +This will then re-compile the files you're interested in debugging with debugging symbols and you will get a smaller binary file which should then fit on the device. + +## Debugging + +To run a debug session, you will need two terminal windows. One will run OpenOCD, while +the other one will run gdb. + +Although not strictly required, it is recommended to set the target you're working on +in `make/local.mk` (create it if it doesn't exist), by adding a line like e.g. +`TARGET ?= SOME_VALID_TARGET`. This way you won't need to specify the target name in +all commands. + +From one of the terminals, type `make openocd-run`. This will start OpenOCD and connect +to the MCU. Leave OpenOCD running in this terminal. + +From another terminal, type `make gdb-openocd`. This will compile the `.elf` binary for +the current target and start `gdb`. From there you will usually want to execute the gdb +`load` command first, which will flash the binary to the target. Once it finishes, start +running it by executing the `continue` command. + +For conveniency, you can invoke `make gdb-openocd` with the environment variable `$LOAD` +set to a non-empty string (e.g. `LOAD=1 make gdb-openocd`), which will run the `load` +command and flash the target as soon as gdb connects to it. + +From there on, you can use any gdb commands like `b` for setting breakpoints, `p` for +printing, etc... Check a gdb tutorial for more details if you're not already familiar +with it. + +### Rebuilding and reflashing + +To rebuild, flash and rerun the binary after doing any modifications, recompile it +with `make`, then press `control+c` to interrupt gdb. Halt the target by entering the +gdb command `monitor reset halt` and then type `load` to flash it. gdb will notice the +binary has changed and re-read the debug symbols. Then you can restart the firmware with +`continue`. This way, you can very quickly flash, upload and test since neither OpenOCD +nor gdb need to be restarted. + +### ST Link versions + +By default, the Makefiles will assume an ST Link v2, which is the version found in the +popular and cheap clones. However, other versions are also supported. Just set the +`STLINK` environment variable (either via command line or either via `local.mk`) to +`1` or `2` or `2.1`, according to your hardware. + +### Semihosting + +Semihosting is an ARM feature that allows printing messages via the SWD connection. +The logging framework inside INAV can output its messages via semihosting. To enable +it, make sure you've deleted all generated files (e.g. `make clean`) and set the +environment variable `$SEMIHOSTING` to a non-empty string, either via command line +or via `local.mk`. Once you start the target, log messages will appear on the openocd +terminal. Note that even with semihosting enabled, logging has be explicitely enabled +via settings. diff --git a/docs/development/assets/hardware/OLIMEX-ARM-JTAG-ADAPTER-2144328-40.jpg b/docs/development/assets/hardware/OLIMEX-ARM-JTAG-ADAPTER-2144328-40.jpg deleted file mode 100644 index eb5a3b9dd5ff5170f1db4239a52debdff2cbb183..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4923 zcmb7IcQoAH*8Yt)jOe`%88QYVK?u=HFeJf5ClNtJH#$LdBI=mIt0sDnUecrY9>PST zchSp4yWab~cYWXe^Lx&7{(8=O);@c!z4toj;`_x6K(DQV(f~jp5TJFrfC~bk22hZZ zQ;?HUP>@rA!4#AbdI*Gy3c^fFcZHsfnVp@DnU$53M-a-%1>XW25Unybe(CTdgNq1~6t98wA%k0jj1IJ}1NH6#Q!QU3-mlBKt1d#k2e;fZBml6Y` zI2k{a%GGVFq~VJx;L2reBn+esfD$m3j>bX$i&f5nQ^@x^PepuFJz%HdSs4eWtGml8 znIpM@EK{v))UUixwtP5_zB~}4Not;icV$NwcnS&G=y_-_{othn^4n@q#{HMMsr!ZI53Nv%`uc&9+$8lI<8z%JlWc zZqLQvmn~7h0A3WBWn(v@GX0L2=PQLubWD42dCdX`Ql{KKtaIhF-Eio&uV=dFQl@wd zEo{+Z#r&+W93B5q5Q~iW^(oOJTg|G6+Bp!i8$?;On`Fyd@sR3bfxQxVbs75SyJigR z=>_09d7#8_dPAY#NKVJz+{8>Z3Z}i?m|rMN(maRHHN06M#QYDf-)$MG3?H(&FpV*P zj)+v*x&7%Sv}9GqVN>^E$FPx$08Y*;kuvtH(w^}&G)H($?qkQjftl0pw-vj0zvo?rpCYk7o`>Sd5halYmOrx`qg(1Jz|o!U0HLl4odpiO(&; z8a~0w<1T7)a`r)b*b_yI6?regUD~W#t>$T78Vy@ncxi%q$XNPl_RvA*v~{3+K#N|F zd-R6g)1<{cg?kU5n{ATZulvBeQc`x;i-99~VykQm+GXIImu&c#rpwGy?RmdvXk|j~ zqMPd}CmoZP-eim7@JZet(Xdw8{+860q5be;^C=^i3&6{=ML~YB{;t`GrPWCS>=e_fZ*J)`99~s0#jxpYL}dt6g-zd7Tp=hfE8$Ida$xJDC%?88@oV`r z*6jPx(fz}F#wN}k>%MVJ96B*ONvEV2_u_h;Fj@M;Exf7o++PEgv5?!|* z3?4U4CpsW}|!B&(15(n2x2-lw?BxB#*H3vcMAIND%=hUS8sx^v|QOwwOU5N=54Y| z&NN}_lF~N0ItZ_boi`6(eER&$?DNW|0!)9JlxF9uqz&RobCOqW3wpjL<+v)15<)Zc z#%%Yn=7bC{$tM)JTz`^6P-xXvPqOh;p#NRZlln8TQhfMPj;OQYoWwLuAx9JoPP)h3 zwl4e);6$!E{noO5-K5bpJY4Ig(<{$!|u#bKmFgJc@lGRC24DfC!v`BjuVZS3mEEHA5wd zkk~Y=r9U7E!~iOvII-Bm_x~44^VWM7W-6bF$D#} zj2xl;KfLnX#J<=+vR{I1JoGzuB;Dl8f~I(OUfKam{=?!!N#9|o_qQc;OwH-@I_9_# z7~H-H?;{&01(6r=2QJNK-_u60b)-pQNdsX^&UF@WX0z7?oqbVYQYvosx1+ridlds` zS)R#L(p~d(%|H86X8cu9+xa2EIO2@gn#1g~jhJ4mF-bA$G=%M{W>ATfmo|8k?6>A> zz1^*s`kvnS3=iKcozHMZ$En@0A46(6b*#C6M$zK7@s&b{v#H8TOg&r)Hi?Q3#pOk? z+}dO41>kW3C}|&HPev9#UqipbLd`NUray|Yx@+KWmM`3znD&+I&)2iHpliB#Tg9{3 z+FCBztN;mI_OmE!5w>Cfi} zXz}?Pue}Qp=>K#>A>^OXEymVo$(Za#aVi~v1l*Fc;9HzlXWJfCKpYLcWvfP$22#J0u`o^ksE)mc6k!)if2Xdw)hTU zW*+$(H_68b3QM28Ie?G2Fx)(~yYa(KKnr#};0vxIfAlTx1~HIPh7i9m%1bO7F;G>O z6*d+HwE$nH;eqS)zNP9BpWb{ia0hSGhJ6Q}xBGotP0qY6@3fcxUY`s!6zj<&zPQ_Y z%Cv0C8(q&8u~T_7lt3o)TGkG$*(-af?J&eiB_D$sa?wyaXgz-IH`Y3N@74R5(O1gU zzDF?~^Fzxx=tO=y^GoEpZ89@uPq73ePo?(BRmr({TNUr!*d^;`e4%G7{KnsXb<7Y1gD2y#k|>)ecR@ink|Ca7ei|SnyP7F_|O_6Zl;s zPgZ*8=DYbpkFSWx3`R42R;<@v%38BX`_SuZ97#au@eZD7xUagq4Em`#q|~uUBExYF zt6JSCFt$3m8fM*#N0soaU2S}IC(muGU>z%K*pJZ0_pF>$RQ1MxsB0Lt7d9JnV+6Vd zh{pb*FB~>K4tQ~{_mq7iXMIsyG50q+z>o_7vwhlBED&d2`nbOEQ?hfDx|c+T{!>+M zYNvd-peY!$dr)CB-bh#Gc`B&55hXYvIG*MfPeFk5k4Tj5%*Q&`8oMdOBd7ukIFxfgy_I;*N));#s# zykM}>xj31VWiw^drKyG6cHk7rO)g7ng(LbV5B+vXx1kO}-j9Q?R2%(%i07HHcnVW~ zONCe}m?=)gG;x#*x4T6Id}C9%Bej&_!bsn=Gln(TD>Y)wqz&uHMeY9b-yii6$?#rJ z$xV{l%F{$+TYy$ExnMd*@zBHwGUB4LofK|9ZZq~6zc^5JF!9R4X^BlFVj{1mag?RN z2?TD|<=%QJ_355u12ly4wCEAWk`YM!s*1-=(1_OO=4BBnyr3 z`QrN$&JH9}c=y|zrX|>SI$D=XeYoqrjB&S!9AVB6_cff|4yL6##~T)~&fi*Dv%<^I zB|v<+(ac!?0=1;h?4MrQzv@V6R4Fns2!jm=Dv0hiavH@=e{aljP*x}W?fAFSRnpi3t zj!-_v;q8Kt9_P@ZlO|Y}45`wtxBBglnFnAaDBSC1Qo80;=D2*LXjS9~=u&x{b##L+ z0ITlQ&h)`<`*W6e{EaqiD-wx4-!b`7Kedxv^kfXe1&Rbn-19<)<(8#t#=o(ss~F20 z+?&L|97?`sZY8l${^=NMldVM*uu|+Oq|oDX67Z}%^_r*Cq*aPfPxVLRy-OYQkH_CT zmF#8dh{J9cWnnC^;jzib5aR5V^xGF^j@0;FeRL3ZnHtG-{s1vad3sARfBf*Ur09Ox z5LME;WX%s50$7h_4G6KmktE*NQ;X+R8OSsMHsW^zlm`|Teo_19eHbyM8`R)iK zBZtHABGDyko7|ZvAd@*tbdA5U*Fv%AZ~4+|(t@a4LYy5zS)Zm* zdSar?U|-B(Hjc)->7Bq`HHMaNZS_adTG}!OGtd@gUGdB^UPDIBK-7y5+GA70O$Zs- zf+PQ^*{4~XD6gm20XE9jnEAApq2N!~>H7BeO8bLeMmIWbzS`RpyTcZLXtU2O5m7@D zn#Ictr-j7GL||)O?mO!3DB9@m!ZdeHuR|q%SYK#X zPp-Hq+r9iXak0sm|8AXI zA=Vd=)t%A@h_S?_BC)m+2a*l5Ql$3AVt9Cz!9mc}WaKz^}b{;uM;{Ze&l zOBA)TRP*TB>kcs8Y)i^7TnD+|LNa4PADx04H)x#RIF3r- zI;iws3E&%dAxjE-dft^I6LQ=s^FJznx0nr(q_~d^PMZ++a@l)GQc!E9rDh&qMkwaz zDx*<0*y=g1=M#CtzlVxg-X&yF`50{#6duj4$*)}ij$^e}50P6a{ib?QM~q3LZ}OMP z9&=vQ{ywkaU=mf$eq^7{*TCVjoT~3kS{XAsE*KB`%DW$7CAZ|SrwU?v}9mFDC0iP9($FtKg(4@ zx`?9<9m9`{VJXpD9Pl9z-G-ld(AqRz;3$>w2UQG>pve|tr|!*in`}V5$VzV<|JMis z&YFjw8}@M(f^~^+LMgjoWBQx{(-;Uum#sB60q=!*I2Q_DGJ8!>!Qo8!jF`YtX=|uoE#&73;+NcfC&Q& zP=Y81WGoOPf?+wx*dTrghP5C+fPn*Gzz|BrFbKc!Ac#r+;7JhE|B-5EWK+@RG-tPC6Qq|tw+)2aI-i1-Sga?(WWNV{T{V%4%wF3vjY?a0;^X3bON1a6M%=le5L=a>B!I&V% z&iFUK5&R7UnMl9v0#yPqS-)jK2*Ccq&~oAahT*e*>wgI9MEsjP^q&1_Sb#@D0)~sL z0*s0OORxPaPyQ+!ykh}mN|25Iga!HeAbS0eIJ7OH^&thXZ~!}q6hU{wfj_8M3&9IK zh#!Nv62yoAEI9 z(SkZTK$$Fbu=oEd3lRg<1=RxnVS<|;p24WmA zKMuqkAcoEe)ga~q<)LlW2I3?Tfu;hZAchkE;qcKE#)JwU3j)fEUzR}q0ws9h{{AoP zey5m;Lt7nz5(c>UzrUwceuujWX9Ro$<$mWwuTY$hm5%in1||J}V-INXi=KklbYKJY z@B+a6tCoK<{uaRen&nJ@*H2haOQvT#Y?|~AuN?;Oz3XS|b=)=E5=6_oR+L8WZup>bs)WMIz${B-U zE@LF*5-vj$9u+8hfqw9TOX^c%>~{J*FH%!7^tDlilTSsi3+kOM)6 z&i3UXLuY8{4E$e#c)&Ih1=$niX^`K7M)QH4?F$+JxPXsY1>FA%RscW~=Bo?4;}$PBpB9!+zc`z$fFcszXrqq3IrWu z&~al5j)Osv_5W$i{bj@O|KT_p0`GqYD#Q6FJ^WxlI0Y*}4W>2Z^!C5zy1&l>(7gYq|F{-lv>sI91Nk2%LLIP(EZKZV005i2PkyDRBTE9} zAo?r*EAd}kp!tNj|APx3gJR&60OV=Kx0`@oM*+Q`j#Z0h2ABchBJ!W;|DEzr0{=4l zKNR>cCH`+qr2I3+V8IrLj_4_%|6SVe7J#mUp#)uP{$ADoHAV#^$hhmreR{1eBx}X@O z#Q!=c3I!eh*EvxPi2r_01d9FR%qC2U6@^;;{>S|yfGsaACk?>BzyL46A8S?NJxmtsMx5eC@83Sm{{o81bBpm1b7c05|hzT5R*`mK72^YOi4vc$H2%y zM8U$&LeEY^&p;1V0)vEvgo=!ci;9X%PyCRW{(qb9zX3SNu)1)Ra4?SnSR5EQ9GLqK z09@w5Ab_=nR`?Hr2S8wbk&sbP(LjMJYycJp4h|L`4gmokT=c^DLJx@GaS$Fn;*dbZ zRWn9PcBEzWT@^HJ6D~APVY30zx8U8d^Gf21afkUOs*SLCL35(lWAg z@*0|2+B&+=^i0jnUs_mNSv$M9y19FJdcAoY6ddyIeP~Q}$4^NanOWI6xnJ}0 z%PT6Ys%vWN>f72oI=i}idizGl#wRAHe*BzXT3%UQTi@8++CDlyIXyeSxV*ZC+65kz z{5IC<8V!9r@{ zFd1*806b!PZUB`YPZdU%!3qIj!BZ1QQIJy*M|hN-#SK)dNdbrfvQ~eWlLBS`Gx9WO z8!#e~@fsBaj~GC}L!}3@@G1jeKLpd^v$L|(VWUPzi2*(OjMs4D>BICu`iMk2pe7F9 z04DusWXy53=}-W)=I?ctP>`jEvCIes0s6aHMOhWyCqqRFn@eNPC@l9gX2~+c>B@B*IM1wsByJfs#FXGaWt@- z0+x8eajGy98E?dai~z77gFX5`8{@|pl%cab>Q%)Sy5fB#T9$?!WuNHZbYsa@sMz3$4Dy(diK6nc~ zAEuj!KrU|ZwVG1c?duy&r#VTAg=mS>0o*)7rrsYhrsDY)s@3;EYT%nZeXJ`h-8*Nj z+noc+HQx_$#MyVbw)cPty@^ z0oeoWj-3LQFypTy#$CD7N{ zDgMZu#K0**h%{PT^n7Cw?af4m5k<#kq>XwC_35^&F+-k$hW?EMdFXiBjM#3K^ASJM zkbD_l9=#AD&RFPGl{``rqh{vt55aF@ZR1M?_dxkXlq?=%?(U+PsY+SdT}7a%bPF$ivvt1lX9Naj955ojUc`z zwiQK_<%l@7BzVG1yh>GAjfB`L7Jxo`kfG^B-V(-H9)mX&@ShB|uL4fQQG9-siyff$ zH`YG*)_7jTA_Ea7`4PJQ&eaY6Hbu&L+^bSg`gzkMT^*zX9UkGI=HzEp%kB(#y89FT z_H*>>&2+-yM<`chKg8Y>m$Ab!b2fF#LSGH_nt@FF}APsw~*~u*~7rj;W z==2!qW5~J?5sX`*{k$oXMm=08!-MPEE$Vn+%wh znWKs4`)F6~KNZTVq)aeuee*DDMZQAje#`OE7qacO?#a5grjEDNl!^_K_Zfz7Gr`@s zc&pvj3z;OILy&&m+amSC-!9TxtVX7aV&;-RtnBrfeRio(7x^6U-VZR@U?OQjAM z*w85FnUDt*jxyKnzg1W>eH48}HFlhJ54;U(YGE|m!9=@y^P^{*zF7D2eS<%v{VjEb z;5`6lJVd){0l-r0nPNm~d`>CiDGpi?}0X12w0=T7%|6d zHAvZ_|EIgw-IuO$Iy7MEOzQq^it}mN6g%W-S8224T^5E?P85f+Vpn)Ahq0+Er(YZ& zqTJ zb`NODr#?3Egrkrbn^eR)5vvt>dqXCIpO$OwXn0%Ke(g0GA5+# ze!*o_LS}PglXV+~AM{B}J}Cb%7TdcABn`4&`AqNJn$!g{z((aLV_C15bf<(~&hGi$ zthy~ixUFXr?BlV%d%eu5vUzQ$|E>?;DU+J4eKNm8(6q=e0G$_9y}%4(^l7UOz00`6_h@D$GFv3b9H)E9zWBx zVkoF`soJ@-vtU*abytxb*i$;5ub*Y5+E`;68{TL#dU=*%(odD{)RXmEC7Z8A@5tJQ z1;5Zn9>aR>8z0`9SP-{{T&IOM8FFciu*IsWM)qkRyR2A{#it2n!hp+>^SB{&#u6v< zJ_r-B(KIeh*Fs-B55wh>KjXm76S!VHw6|w@<+~~@tUVKuvD%@-w6-{Fck+dJ^Q%o2 zJ%IxN*sC0kgOdi5qbzit&h zXb^PdYoh)4G*WvS z*}%*(h4Z?WjW78xhOMd_2>Qu8hbjjK&G@r!6x$(sN%@!za+ygYA(rRNpYtjprNgW_ zo8~;KX6uRTc!qA6y5}suIYw8TmN$wmCnNdQmeecNR&#D>GG+XAAJfjlm2VV7AbRAC zB`XSP^0bSZde|9lI>uYtw+Frh^wB8$e7OrZrK%z?g?A`O^Y6O1g;g|V2>)lSuHC?WDbmkZr7Om&UKs!sGmsD4<(mF@P_elYX1nk6ct zJ57Y(xNUE4m(FFd5>8A@Q<*DU|2~Ucct^J1jh{=qGn)!Wi=YiV4ApjHHK%XBc5UL#t{8D1O?Km$6ibKv*b})Y{%@1wBjL4p3k%H&SS?)B zbCwP6fkLoUTU8msZ=)?A7vkB6OTU>vsE=7mZM2w7Hm9gG)M4^|S2=}?9!-VSmBGh_ z3vD(VY-crcOlvzUvTE}Bj|Aj0(cZZYY!z*D$K?H*|4dM>my)e5dW&YI}=$CgAVPH&mi^5Yp! zXOA5Z)l!4{80br?_z^NAnXo(o55d<)-s;i=;uMz|F+;Lf|F!In%u)}g}Hhns3efPunsSWqQmtwoC z4!77klK{1drJ2xeSAw_tbg7tpF8KYIL5q;SrsG72t^mbFZ?Sc~VVvieBg2V>YebY9 zMy^^H{*ANzvI?ZRu*uZ7lOy>G&Ng_jNgv2u>R6e(F1gn#ZY@3%H+bNb+bmFmg`eo_ zWbJb<_=ry~r-t7$_l4L*l~Gv>_H5Vj4EH-^=G@xT61fodLwQUbyomI!ZhZS2oz~A1 zEOtn0abio)Btw>n7`&BqqDPo*Ul!SaTjNRbS5l(dtyjd2PmrL>WPss_;Pjdp5bE$E z%RsArxQ$lAwq6ZW&1HIA^ix=6v0ptyE?s;MD?vW316{MkaY;m;-PW!!+fEkwTWshl zB%6D7g~wm1iATWjnSOk#zGEIyZj2F?-8oCZH=?i2vl6ZEAg){3ThGa21X#_l9+TdV z;@>fa9~CA&8!w8L{m?G~!|CKH6pSVM^LA&wtd6ZTXS+|XqL^^{^W&&bipJeUMEQ~2 zi5S(w0XsWdfw)~Ok@A%X=iZK`K6}GcuhV14cXdPbr82g=SsE?5m=J=*&WS{9#D*dXNgVy*`z&6%sy+6r3ZOYP}_KI?Xrng6XCx^*E1C@Yi{2DKT zdtw&~-Nd}W{tG_1J2G9i0ZN)ka}rLK=U&9;Oow|@`-Tm3_dpC+1f$4{h+gWTWX3aL z*P^q-!LI^0cxeIn-!C8U6|=e)D6EBU>KBR{1hZ$^6AkScLMkjAA4c0doAP`&7Kppr zAaRg+;@=bz_oaP1o=UddlC(RJAmg6U4q-iCm|nqbfPc=deuDzl<(gefu_PT(Qh-@qz5)ijwwnEf#s} zc|ZS84xLQag^dxod-{H|akzVWUUsns)~c1&WlR|d|zXg_1fC6_vn$Wk`|8)?Q{~72CH9`5z|)c`|-Nn_U47JjmDJo-|SK7l)fHt zCzK87TKsl0(_~IW2kx3b=utdi8z>2WwO$tetEiO9FRsiD37EERJCX{EM;LiJrwqUMNFIjMkjqg_jPu|YwN)4qR zD@R4zhlAD8i3~V^S-|6st4W!5g`qtP%x43B=qEhwOak9%B&bMrOzm?&s}SqIdc?9e z+e>KT!0UvyGPI&Y8p>@FZ{%4WKUP(;W| z$UVSzsU_lycPl!Icl3$i3_~}!U6osvzrkdb-u43#9skz#)OcSAQ#d1`N8gB2O>?eb z2?OtJ()gD0r=^l>)RMb9J;_`T2PaqKh(+0|?`*+Et#@Y~BRP(>ozd6iOkz4?>0|rG zvUIqanY_!qiv@tR7;!(2auKp%Y+EbMojZ%BdyS9?>X`Jf-HRk$R@!LFdqB6f-Z4$S z(6*6je1ZQS2)GB%^2Jb+J?!=TuV4C~!WocN5(s9u29MjS^>Zx3Y%4KVW#p;FGYcE! zq$ZrO7|P2#dyySg9p>Ew9|I`Phy8=-%Ma_ezNXz=inZ10MsvpISgrCilSS&&27ASyNv7eK)ePmlW{E2WS^u#!cfrr?`!)SE9wRPjC_`)EAcIaoa4iXYPRonOi1Yl}lfdiP8km1!wfzeB|3+qU+N_411}D;jH=M z=h)%`gj7EwxA`wh^a?pN^KRsfzu2o>(s5fqQLhnhK54uW3;O&=6+@BzlG*CKtW1u| zr4EJ#e-ieN))`YKYLK#-U0`G6p4nV;3EDN8@*9Ou<8DH0X>FdZp3d8n{z3c-OH`5b zU{g1Pdz!iwq&B{(cQww`5pzD-FLKkgg|TvJzf9e7I9pID*;UA}q7hQJzQW9wT?!dX zvp%O%Al$l9DQH_*8ecn)JKsp0cda}8?2;gnb^&V3zsyxCuO73t=bq~l&?jO^4s*N> zcbImaQRMAGJllzYoGsWaumw~$`-l6->d=rrb&M-$%ck$_V%aR*f3>{T_aJOW>67Tg zu`$gFZK9Jk#>7{y{3YVVqVWW@qc9M#i08FKA;~*V=N%Zgoi6iCBXpBeH9yy$9@m%& z@C$V3jy4<%szo47hVwAY-9ldS_tqFi_w_WM*DG2pw7&#aV+cYc`$w=2b<Vj#Hg-wR)ECSxhxkDA>+wH)XU+p&dzA>B=pF zcEcrK|9*m{=#vV3IuS*oiFQfsJozT>Y+vm=qPN!aX@YNyBe**C6!qK+OP>{7nd8@O z#DH#Ntu{`n@vVTmB_?Zl^TPbW&w!m|oiA3+_+z^)K6{cE#RRMdOWNf=k|x#9S<91If6&I0 zroJXUF{B7fPuh@(XBn?Bdw}HlZ0*WiSVV8%aoypkAASAhdnE~}pCWw~9?ml3do@37 zl`*Hn%TX>0{V}(aoSz$P)rURW&or&7!6wuWY46wn?5z;%5bC- zSAI-EvU~ANyN5r9UQny3Hvd_%bL&GL>>YP?CA189Dn~-1o?K>pK2qi{2t_5iiE7f7 zb=LFGgZ(48XKV$RajXc#4V}Z*>)Zwfj||f~a*V36YvjFRgNZ)l~F`X}+{m<1?>N`jRr?!+$!i{Pl8$9(=*VMEC5b zt*QWe4Mx;Pq(6}04h{%nW#E#>fW_0u%SfqzjXjL%!A)+(&Lxf(Ml3WIfX?nUW(i}t zB}JHykc~G#z9f$4I>_?4XM16^4hsi`M0~vQwPMT5SWC4S<*^8+;;D*r%Mjaz(bA|O z)8tbTrc|4xO^cyv|93nOqn^?cl4+(FJ)Jzrh>{C35nMFo8M~a4t%MBg_oQon>c#Bi zXxKS0SooPZ+H6k}no3^7Of-h&X>C+>L=zi6D)E@liEzEj)<-3i6eT0sYa>!Xsf}i)Sak8huGv)meMNrRG`o|ly*M5zY27((Qr&p=oBo?7EJ;pIhabegp5@&_@ zrOIc*Zpc`0k=b;~;}U(TyF0iYdUiP(oa7HUf=RKuVj%ifxzg2W@zOesPK5hNqU~v; zWkrv0PK)5(sNj=z$k}+~y_7#k+&yU@kKI!@Oq=bDo(_V8ADz1$>Fz=l(g{w;RiX&= z3zBFh5+>dhemIJuZkeIu9y2fgwMjQ

fU?Mv*LQeAr-CPce2{endWN&t)-mw@piv zNjh`WSwYKWIlK#U`WSZzC;4S`r?UjEa9lbR*3p zo4s)mVJd8za8*e7J~f5zcz5#b$%ukkk=Gel-NJ>p=X(iPq9vQF%KnC};x4WF#{F|DhB10H#g4LI;HHS+Q{~|{R>D(J zl%yM#(webXU--DB_b6T9aT9u1j!G1UU!8eJ;?7tT2Q?mj`%=~vFmr5r#hxcMu5!h=S4R%`}EBtJ=ARRNd`f|no?e?C}i}Mer@Hh=J4@y7siu!r9 zp68!WH%E;bv8-hcz*i8NM5`Pi<;SKb>pXJzx6f^(YjB9(uv_^CKanTDM(Eg3<cok5PQ`PPYPaKE=HflJ;KprC*s} z_xUx#T$w>!Jk+_^Le4fnU>6~Z9ZeSN$V^xapW&zAMdd~bMQ&qV>cj_jw1qj0=4DhS zF5ABQ;2hr=Y28p--LP)iYJcF4zn=D>uxK}lMsX!pt;s{)Fh z79B13Y+pgD*M4}*N72*;+3pv){SOnHJr6(xse`(kEzqb1viTt^Sj zQ7!qrZrfyu%`EymUqXex{;66>6=~VAWzG~LC+@{BoQePKq#BTp?U&$#o`ebTq zlIP^(Shc8Kb$-HIB#{cOy>#rS_=uPsL-rC{t|U+P*7GP=kjR>LPULw^N%hhcQfHSZ z$p^?UvbxHws(X?nS>!~s!eXz+^;Xs7avS=%R-@TPS~XI|(5F%^al6ILD+T?ki*5pr z4cHz{aSxH+O6Y&kFiy{uKS3AH&4^qx%8?|H*SyQ{BBx_&itswMJjfrQjbsjTFJ)XI zQFanPCn_H55K;-Kj2?fea)(ebSm{kc16MbD8#AAEtmK7QTnvF5olSl4+%JtC|7f^~ zxT;J&aHKP}P(wA>Z^e%^@-kUv59S^iPH4hC8Sorx&p|6v%qWjv(9fTofm((EqL+ja>B!)| z9di#t?1olS_fBJ`!Yv`+wBa$x3y6jJ?aqgB*YOcyxvz-<*(V9CA%tz$4ez$f8!agB&4k&q@Y&#e5eINuMI$uT-70*8I9Drq*PL+^OBCS29r$_Tsg zZ0SUp?Dda)1S8^kGW2>PDd8NA0|K#53y6z@jB$df#)`k3(8=CTM$0djlGkk+EW9gB zFQ43JDQZU^c}*m+i*;6#(9um1cph)gbMQ<=XrW$2&@RYMGj`0>M)JtKIWeo->iik; zQ}_h<7cp}A59b-j)gb~KpR(RkBvAtJUOGBrA(fYEPxW+@U-g=bjwO5H>T*2W64Z{h z^~@K)cwk5ok6(&olV422o{KCoAmwR!9y~ABJwj0h1m8)QA%DM>O@#Ka=BR@d-&*xDzC}@r%gwi z*9N@DY(JMxDd#<3MWm%DK8j3HDST3C?`O250G}Na=9`?cTSe1w^uv-+Z<@1D27Q;E zDI`fI)ruy*Mt1jEWFF7lWo&!BZBw%J96D|<=hHL}p%0|)IdV2%^tKNzA52#m^pihb zO^zM9)aY8fyj85@;2~hF$(~OMk--VcDuM4y68o?;R{7DEcv8k=Jp5Z2xlMF}3a7La zyWD`gn<#$OXO*T8M0F7_pGL*bkeXyCw%5COB}tt71XzyZ)E<8eNSn;5*7|6|@FYc! zRd?^ojgc@}M1T)(f6%|(k1kO*Al;*J(>V&J)kyEBsHjrN9m<8;ZVdpmR3j{TMwh-<+;(I`~F`9~v*t9=F84=5?QAD^Mi%>OO^Yi94TWx407VkEH zMbv~V${AC4ZLPq|O(FVI{DQ@wnKk3n&*ae7I9Jh+t-Hfdcf1*vd8_xZjfXD$Q7zuM zqS>HTdzZyei?0YzecT-X@-h3lySws+Vm8sz0Ya`xQFeCs^r|U|@n@cGKXPp)9{et3 zo*=}Q++GeeOGKe)L#eo4VWH)ltf}EO4?*rSjRMrD3$FZpp;Yzot!e{nGI68S_w6>H3;4sO65 zjtf&%yVLdj+CHeazul2=-{<>1Ab)uDQ%g}w#fpeZx38}|nVD!$9nHjBC$AOjb*4e% zFN~R zXeTBw0Y0~nexVGXG3#47qZ}Xav2mJzp!j@pCbMtyK^3FSd=u@=(ve$74I1IO!IZ#? z;lqWeEy45C+EKz%KT5lhDgE_M9G@vuVJJ=H*|2fOKRp##kFT^PdARLWm{!~^T<%(t%44VfHw7hFKi4OzIHYP>>Kwa}OV}co zxA#_)78D;5dS=k1putl)P~ygLEKJw4y(iB8HoVWwyyEQYu%r)Qk6`kjiiqj05NNZQ z9DNqio?J4CprUqL3Trjdn${Q4nk7tzi<0sUH^3yXuaez6zK!5stroOLW3u7ni)L1` zXGsuV{pj9HxUy+8%xb5hR9T&5i>v6d)>b^(E5;x;3_gP3RCUIMHQafPZ?r~xiTijT zWM_#$G8*P&^j>?|^y#)YRCfxKzlalX`X=KEPChAxRQ*ZngSyPc}q zZ<8vbYD32lp|0{MQ^CU9*(LUg@K-`(VE^Zk_2K~MwflKguJ?>Z!=8=Rww1#CDEN`I zvyRGPb*49*0&!P@xwKlG$r!ABIlSlLnpg*b?d1!3BfPkCK*BL7d zokQgm8}xT!S)$7xge(xAh4kh~1P7s2 z1z#gKlKc8+y9mHNyeYF@L@`A6EC4z+VxsqD&Rna3i4Z6 z!KyE=8iztm{vjuA$bxaKO#xv?ijhlueM1{^d2Ji1yh)3Nb}y|Aghz2I4|PYkregZp zwG&=GQdSV4OuqJI`m$2W>tA~h^nU6^b)`NZwmE@I8LHAOeyNC~7QgriQ9jGomZKb!q0j&ZRmnxn^pD&WMDZCz&2lO2mdLKblF zJhYj1q^GAT%vS;*9H-!6RX>B6{I<>NxCq1%aN=V^!p5tUB%@oQMv-1!)Xjrllh; zUt8tuOKt^pKQ0w0d>Z_ITCq$<8Ah^+H9i*HlEnrKnZ**HSSOxLp^dN|7#|jP4jgH; zkALO5afA&Po3})xxyQyoL?MsjV5P0Y7L@c3zYB?q%Ct8FcLM54x}a?TX((I4dW4gD0U$f@L}jtm9Kii#?m zy9dEpg};N3et^aOLPuqM#F(<^CFG=d;#M-tC_Q0$@?;N|J)Jo~=N5t=lI=0tr>{A7 zaN5ge8qohl(v-Y=x~|E|l9>;BW}8MWRW35T#o(rd$;dXLxoOaIX?gvt zED1vVKvD3YJWGlU$|e`9j$8*TtM_gezjYD1!(9g$AnfNd$3)}e zg*kR>Xb~^Jx(AA4A=lh8L}7`I8#WDlGsLAz*@h#9b=+vsL>RDMT9G~F_r8Hh5rWg%g_ym zVcd~Gaw4}OMCT5D_AssYGNnSMPG*32d~ z6U+$H-)1ss>YW!R^JXq5iq4p(#+l=03>IH~2uw#exfY9F4Gz)W#2pzRlO zPZEbSmUdJlogx_^bT(ScQw~Qhb;`|@o@`l$DPl&k#|fQ$^cH?Cax&lYWXRT+G$FdM z!U8p{q1-R7p8~^1?G4G+6kICiJd<+Q>;}?qqgYo}qTh!z#V$ z$vey>=iJ>o;|sE)s)^2&vP9j`+3)SEp@hf&#IwU2d=HBrNs#OB2aJBzH?S`yP#ba@ zS)s%OqIbfy?ucD$gXY|$RF1;P30H*F`&e zRgp#LJ$1t17h&aA4CA8$IUEe_*>qld@bt8C7NbcFKhxojf}aWrCx}BM){Y;y?Or>g{R?T zs%EODp#I%LI5gqq@}s@!bjdEE@v*y}=J*pOYnS0my5rlvqz@FrUNAb10(p|)M^IA^ zBp-?S!dC`432`RBZd2^sNi(hoWGfWR-K8QueUaTS@C|U~nF~Bm9c4}IV753icQTYe zXx9inJ}vlRaLVMMEXHNvG%c81fbG{fmD#=6L-&k~XO1Tj4d)g^P~N zbf^2H9)1y-Dlh()!mMm9w)hswBu@Ru$qEh&Ontj4<7LGwN)z0&lv=h(-Y~sx*y82$517bqopKE*(zHNwAoYFlJdO6V@mcK`tL0WDp1S;*`HnBSZmsQRkePd%*5G=GjnTP zNHI^cNMY`nke$bpHeLKNbG~GgY#l6CzLPZ}e<7Uwvbs%$NZVE|elB%Sf5;bsRnuAU zMsNN*@noy5Q9!Mte!y60uQ#tYWhsC0f%ajBzEz~R?N>=R{J@}axmmex{9xwQBw<2o z9rAqZGRIB^HoK-Bm+A$o{A5$@w7U9R#Q|zb8;_WI{SRM5bo)(trmY~1W6Xx;mBWuh zU2Y<1gejiKhv!&kcxMqDi=^cBaB-Ul`|=;?SEu5QvaxDU4|O1))C#G7lMuF;taote z`dVUcK7Ctr>ncD;eIcNqqBq~8pM9J8{nL48Y*^|y%~9noDqDA=)unf|pUbCJ=8SY@ zTv-Y~Nn2jLGVWSZMB~}(#ctc($Y5NZis#p?mlN9YH=@d@VKSK7yW^Dmj3ezU!$X?s zL%%bOuD&3BcqPYJ&QDr^j-#gk9gnj&F#K9a=!5>gOP@kY>+Yx!TZol2d4<^;wd_k7 zlCmII;Nm*qO6!h%<=Hq7NiFj}y5$KGZE}PrCNMPYQv7_OqrN&i_cMuH_sS>mTI8oBrE1#a#TQysNk@)nlTN0;Io!ymcEg%N zwlWo#ci&7|LE@?nh63)!6msr??vV>UnhG+4Y%y&c3t<>}!7-HEO^q3z9OOYADlF?Scwxd?nXDI@d^m3^SH$>>Z<}{;kjOVTI-PEaoXJkTY~K>U z4O%34Q2TgUXLjvlYyy$6A8cdfuE~k+gkpWH-gLV^O@?$76MjcoMvUCn&Ak6y@v)qb zOs2v2DKF)GvB%QRFq+%$A&T;dcldyhFZI$^d_lWx$Fi{sTn)t1H_)>+nic; zg@4Y&Z!!H=bt=97iL&%a`VD+y@P5}hjk{YouN_klA@yz6F(!tWeW(vl_E4^GgGzkn z56K5_)?Q#yV);;HdmuF3cAj3bt{O4+yC>o~zGc=YqK?>ri`{yj2In!gATtZatNXH*)GSZu`9^kSU%cGf*=@J!>V` zE7M}-y}fCvLJxiw+B3fQSTJ1z@Lp3qidw{)rYhKHYZLmt_PMkC#a7d)iC$!^H5oFQ zmdpumj&lMAN>2BHr|-ADOC17PxNGK{0j>)u+i2Q6!U-s?{2OZXvnU&!j&9SbODUl7(`2 z;Tcg^%L3OoW5QbYrrBG;+k@8%!99dFFSRx%-hV5yM?s_a5iRVgklK*{qK_`1dvY6O z?(-tbz(e#b{U@mnv(w%;@@|S0Z(ZSBwC8VWda9ng-wp~a+q5YOkfL7~x+^xj9MV63 z&5u8QX)-vZI@Xb>gGKi7Nsg|@_p2uULfH%n(h;82q>*-56gnnCPMOv3?uVjkjjVzc z4XIVbm$14^!>$21QlTPxjzo$$mF!(2Wlwr6=?Df~>WSL%`Fnf!dy8%vmipHdSh$`g zDa60eLO#UCL|S_8w~cqmRDHNw*vy+UQd)8zWa72bPd!CIx4^$%dvp|Lyx&RtS#JzFZZIP#y7pVnTy+C)Ek7ZF51Y^7b?{6=o(mx&6LY*FEbYPo|@qps-UAQU~F6 z5^~(qGP!hzaf8z^z*@qwpeSe1%cQ##q@ zJXvA=YZa~r$6~~RlUFS3adMP*%WvN34YwLMO)eHIZ9Keso)ST4I9_GQjX-c=qUz9h zqs%{)ZEZcZd9D4y-yO|>b#yQ{yc@1$Md>nRP4qMT7aeD@1+uO&ePTr%r6n7}Vl}0* zH>}_N_VBF)Olah>WGJ+}Ba-9vVr58>-m~RSVhnvM6L0Gf-853v$@Z{YG?;G858%U= zCF2S`rhKHNZeDGB82BVjE$K`Jk#uX|41d||N74biOTO~WwNcMjcN<3yWA(dD@D=}! z^T7Xn-N;iGgH&WQDOw4B6br|U4v3|2r;g`}Y%zrCamlHgxlgE+=^e|Xx02VfD@SiikA0b_T^~=515pd_Ps!Vv7$RjVtzuXEMc`Q~~}T*plm~mB9c0@u~<5*+X{wfpF=( z6ba`s^?)0;4}VkCZB2s3X7?@AMg@8Uu3il{Rc=0SSd0u{x~lOO{;Wif0_}|1oRuZA zc?E)RM-f!>2~lCjap$$od$S)k=l*zNmXU1w&ht64j?+zQeuSKnpVh)BE-*BjE?tE= zDkR*|zY8*+i3Le1etsB#<&Q@`Lheth#jeVfOO8IlXRAwkvqCZWb!VDvGVHM1O~dD_ z0fN9cBqXsE2d!_*3=)G5R*&OiIfI2XiZQhxjhiF|M9$&WJoO0`jHp`Y%bSvvm1}ui zbPrrF?J{K@63yhvg%{ONi%aZv`=89$HH-@Hd%e)U2tf8#*L@l-!yF~pVg8Es)&ZqN zhu*D2e2C=s8JXC-eUq}o)CxaE4o~d??3o8&-Cjt~qPur`KtAXGXw9~|xDHBwIk8tW zYrq{=h!P_X3wS!^bNp~Gkvw|--rF;mo3F*9-#m%B)-b|5HT}(VO=5j2YToks88-TU zgfWjW^j#9s%=W$>AxQ$Rzw=_=ge(kJVbgr+r$LA^N z8R_bIbfTEA3hSv&cjLK(*D1mOO^^zx*hY>aY^hpX$ zf;8sTbg6P(0(<*RsApe3WGqP;)OJeD%Vg?j*<{GLl7-IC%UHmsNAuZ{p56|4j@L(g zoqrtTJtsPk5OxCd2AN|RXWQ+@sH-TeGW+pQdhKuSLl}`c9-_??t)HecwenR9tfc1?4{|lF7G`N z?^93M>){7w+cQq65Y2jAW4_jraWy|Du#6s;Wa+38(!`20_A|0mS$l5pOjA4MUs+hx zJcQa;!P4wy3LiPdGi~XWczm%LeKZe*aDoK7#&*V%l3gwPtl7Ry1SjRB3>lAAN%^C8TQI-wvQ4$< zg>bNPT`yPqh=AW9y|2`N<3gL@7|0LfNIuMeFmzl(IjppH+HZP(xku$7m*5{SL%G7U zHBT^Hcsi#&rIuziYSioM_S6SAAmVPv=vBd2ewL*9Ir3cL-T#NMvxT*5U<T^X4|}@yAj6m>`^qfoEvjBfb%erT4x> z-+OGxzR>VSenKK-&GwpO9>J(aD>p(J=wa8l!L_KTl&!LGwu`e~g1s{N3#Jzxnod8^ zsYF&(|GCM!*f_cR_&4f7N&c9)3wIQ6#$qE`I8lHPIR`~%EG*<6_WZSJ4<*kPI(Wxw zW$S@Q6~aLbKOH~}gLvJXV7Ob{U^Z&SYwUa zLQ)RK$(2W2_l$&oOA)~;WGdHDLKaHS9gs1mPCef7florlP_Qs@E3#q3FZNHXzo3yV zZ!iXb@HwZ++H??1FI7@eE<1%<_SSfOkfj7Q%q1?C9ly^|$^6v3Q^`J3B?k~9FC@Ah zP-yN@=05LAQSXS@@#bA=(Rz;)fhzkze^suTI7U`sdfX(7G%n-zCBALKMG(ex(uNNz z%UAj@Lz0moI-XNCcV+1?sP=0zdCK>70=AGBT$Yi)JVR9<)Yqr*Oy~c><>}wP@?;%+ zTt2?9>TeQ`+3btVf1Ln)M*jzQh4Zb}Q?Gv&q)3;!+0}ERzVq99x&7PyI>^?coHgT- z@g>KMq15Fhr`ZB1_CA^0TLxtTHSyQ4J+^Q#G+bKbN0}dsnGu4k&1m*F$=y ze@=5@Hb1At#LHC7U9cZeeRF0|pQ*1GN#^_MQhlJz$U9B0@n<%x%`9(EPmf8u0nN^Q zwk8klPq0xew=^|>Ydow&hNn%F$^dj&m;+NdQRW(Cx_T_QZc`%?S@f`hU=pnxs~fE^ph=vNx8)1ggzib7{7 z{ZeH$`50GDDv#?ch*Rb%5c0S@s^VUdeg8=Ah^L!p$@lvCKreh?;I|c(hJ<5r&apw| z8U6-#T_a?HTl+BC8h!`x2VP)O03q0Ir9}bluM?#A+jUqo+(5ID@5%k2Oq?SJORw3CL@sqWzuR^8AzHyM( zG|elShvwkuJz8_2+ax3tAQTUH)o@a>=>D9U)Y;gW@jyFK=AX9eBqIHk-{ZyWD>bmz zlp10}a@Btea^@7^*_WZYpIYqv(Z*MmHqbWaS25?Pk9~h7ykzVa8u3|?o z>=$2F6&l_Tdr>hBf!1!Jxa){LtR8KI1`=}gUnyVk@lL&7MB?5KAVs3FA5tI%bh1v^ zEWeH4?bps_&$iYiRYxn9o}XaK(@94<<=ec(Kcs9%IaHaiQghNsdEqOzYh{f~xP=Yc zt+O_?X{(~?k+6K&XGfQE&L4LJwWD6GHh5o{%NSGm2+nRLXR6cro(xX=D(p zZ+`Oc5fRde&Sf9gHL8EM}y+hdtMM#Ide*CmxBL zHY+TzE*oooHkg=w00+XM4jm`FCv$eT^6n$C);|;8T_7Irg-ey4di;TRNa%Vz;iOnK z=IMv!prV3j>?GgQpeH1C8};OUz5FA_cB^eF+zhAbgq9)doBJvw{YCc<(@_*=9`#V~ z!uJ=uOh_j813v1!v{TFr^WMg+zx_yWdedZE-sZd9=Y#AAG5kvXV_s79HjUa(A#s)~ z|KOw|*5s=No5cWD!NqhCNQ=4h2OB$_6lrlngr%4wFnwJ&#WKE8gjjFc=?0a9<^}`) zijcM0QHh)Kr{5-f#bP#|J3C3=%CvRM3iLn`yx^eOF4X(34?#m=fp~kV6xR=;DW{?+ zVn=LGT4{Y#Z=IsRiZQnWSh#s-HvIoQrPkhOcLGdnA(@xQ19XTwFRG|&vl-t^<7Z)% zfaL6~Ds0{#*g*U)=L7D=-HcMshjTfFm89TzN;?@!Iq2)&iKP6dNFrjWJMCtI1KU{= zd#2x|rVaqL*Yq#VVid>v;HIKDBbl~Z&Syh+Kd)UOJFu5c0oQl~7S5{9h2&gaQyxf6 z_lWXZswIe1==aAU$bj<_IYGzt<%UoiNIOc1=1b43kSb5U{Cb{A40QlU<~+I;?wP_)*OY^4~4 z0sm*>`kJ?$QR{kBe=>t`l0p0p?gU$JCsj@MRO2-Y7u8xZM$GPwaNbh2BUrbrzL4P+}ra=rp#Z z|A~@F@FQNdfm~cTtGXP>`;p;Fn8vB_!)K-ULFb$4;qj(+zY#-5-dD(lELFM&=;n)f z#OC6ePlhY|&#h=uS`m_>9)RjS9@~HZd4hd?i3)>|)M$2JkNlH*oPp_$L#ej(O8=l4 znxR7TAlvmr3~YE`XPdfBeSNCvc}5Xu40Y#QMO5z<;YvDXOYw%*<3~RY0%Vd$hjvf? zp<~T6+zh`Q2{E>(Iqu<^1BYE_gxt!@G0#apBvtOM_TGU918HTqm{i%-zh9-B-}7z- z=~@;NhFW+JPW$ZEmO2(t<+R6V0@+JC?hWMQL}gpu{<4TAa_^9&x)8pd+>^JfK|=*SW{#nU<{S)tl_ zlTUQQf0_P5J>VOdnRcz{nk;hmh~RUJIoUiYnlkuQL`HvJtBjdpi)}8(Fv)K!0)uT` zVv6QT&fh#`$nY2;xZb@|fOhk?B=-E|xteOrtN3sSwmUn4dlqaMI_5Dsf_fskcls$mUnmFt!Kc^WLL!2 zF-`fHOSjfpKi*AGJ6QYJ)6>~Ti#VW8{vyxjN5-#Re#%VKmHSre4t>Y>oAL@syC3;lsP&xqdwQ%OW@s?fZy46+7kNN)TKsS14= z>l=_>n>lhrbr3OmaZ%Q@vx$6%)tdg>pO$cM!@@1DmkYQUOB`tB$+cZe^uS>(6#Ls&HAnwuepnNe?`Zc zqmQsmxuA*?Zn>#HX!b&Piv$WIyK96CKm6tLTqUG@6R3Knqu}ft7?57NH9BxL)gS=O zE~obOcTz-e%@@uUDe59Wlznxp|XStj3^5W?a_DO0KkA_liB0^)B6&+>K~Zr4)WZut*~u5%v&G;a}0-wD`MRh6@NtFc9)she+MzxAeYpBo+?E$nId3cq z5U|C5Up(c;GlZQaUgF;lM%q`Sp9qYU?EfopD`NPa?@{|vULo%C|NU*V=i@} zG^gb46|Y2Uv|cL*z>7$W$v^uCl2@Ga5jMGbHzdlKOz_K`>+z;5F3j|^%MLZ-H#xL_ zs!+-)%*>%M7W-Xgz298wfJl0@tI2h&X$&-Xe2=AXg}11<cIQuoH^&_FVU(D?x z3X3kWg$y_SdmQ=ha?4fEvEF8E}xvi`wEIrcOu zCcq)c_JtUxr2VBcLFJGoxXFV(r?pp2w^1uFrW2tzk`v+IwfbgOb&&gxl^zr%Y6`}hp z^0AT7@k`-2VJeZfDF1W$v@q>8sz3og@hYO$^Vi6x#SYoY7t#x)LSZpRj>dcFvDnh9 zUGh>ppIIrOqgl^x!>P9Ru+mmhINd+jG(~=xPkcO3i_8<}?#Px*=>%;|_A*yf zC*jPU{yphU!GmbzizZ<@t_!YSDAv6mtgzJbHY7k{bL(+6{Ed+T)(Er zT|Y(>N_ERY0!K83KqRKG*%foQZaO8Ky3>282D%*+RS&YYd0*!N7ZS=9X4uZ}`7@Vj zy{+IS5DDwy$9=1oKx{0a%{t}6ft5;{Uya#9;`OApJY_^p@7mB{?TN6elzH}BI%r}x zGog(O2=!PnJh?i?pkArO(%B)+Rx3#`jyjGWZGmh4a~Jy4`Ytn70^HV^Ui_^%v<@C z-Vq`^z5I0+V+z}0SHC9P$tWqJ-+etr*89=hPqQbnz22Ps^BG&Fz zRs@g?*H0GsZ7!;E)c!JCZGUg`sSkRXD3g62#1wrrjHvXUot-7a>UCX_SKX17oZQ-K zLiQOlEMBVa;9v=Rr2!w+mrMB~>pQ!iaAgnO6?qS?tM!8MyEdtPV!l`LQ!s(VE;mmV z{-~)mG5tYO`!XQt?rHR?A&R9CQ7CGM#+WIUHkcU+srX2Q=^(ynH9N+)BVWJz4>tVs zchn?FD^PIeO~6#8l{W~%X?GK2^p-0ie>Cj?N;X>$lWtK|I$-wli!z*~N?U$#z|)lM z;&MUR^Sf34)0bh+T^;h zLG@!o{|p`=Ys;s67z&v>awHaaS)_qVcDhATrXcHh2|9NT8ZAk_y>(@ypo*Fdm*Hci z*x58|{%tw4Gqm&o{`y((i#jpyU?BdhR8u(dD8O#tM$B{ktY48Sb7tM?=!*kjc@59x zCc9m%(gDC6gSq^@c#E55lKI=> zJ)Zn@K$u=lV#Xd$K2D}HAx`=tI*|lvD1a4;1u@cxdFKMLOLTTIfe;JX=xT6_Is)lm2BzUR^0TRB-_ zfk1zG5YWL+Lte>5guL(I(9`n+3Qq7?O&7!h|RKsccr2s;FPOU?R z*r+N8ZuM3&UKPg)Pn~3%8`}rbH?-e>;68gEg7Z5pMgq3i$wd_1|2|i<-t%gYTOi+b z(;VJcD75*U>&v*|^zR{}o`!`@F9C#hjf^Z+gXD)$(ic5eGO-;tt@1q$24ZswRaIke z1T_~gsvsVEn(k7g%ntNOWX^)_LrZvPokX(qbGx^n!(*!gcV7FJK#;8m?8?p(3szlP z3T|&CB$p#uYSB$K!?+{5t06SEtI<*Hdnt@yM8GtJEk+aDdbTs!3U(T) zbAZ!JDCzg0Ujf+(vF}?2`F>6z=9S&E4_G3qroV>9w%K1dYYq-7Hj~Ls$X(T|cBEds zp1`}b*~JS9z~H~drZ`J%T~gA7=ib`^pJ!mpRSLENQ3o=;inJcN(jr%`Set#IX(o&1 z6i3s(o~i=f7IkB@8+6<^!1NDp7`j~{O4bEjx|*@$QSkmK=i>YYUi~A| zmys8(GV7-ByF0sfDN54}o%-4K-7k9Onh_cyOHTTsD2FxoFN;p`h)rTKl}-)i3dJ$} z^9MXaUS8GHb!~k}m=D6E(}pu8XMWa{H-Z{MBfHqhu~j=<^}x&JY31=2qA+@0hLODiut(%3k;)K>+K@bqNxm*U{lPT;yL zmEULIdA(>*U;{R!K8EP5HV;^POER+Tdi<8h7FwFpfR&de^ORFp@3^}z&fMpJsxHlC zZvT(SSWZFizq;7}Yc|$yoqCzk(}=Brk)Z|M6PFSNg{R+)8HTu3r>QV##jf&k;Z|VW zF{6e8DJq&dFv=jVAYxAsW2P1uUvDuarJA5wSm1VhTnqZ4r z%^~R>&-zG(a0yWY_WJc=JN_tIo8Mu~36U|FBa^+SDgwh4`ksl_>_{&O5VyOnWH@OF z;#(l!F7O80j2#4|GjjY{E+KzKP(2C4buy0kNX@Y0#ahSN`v*s5_$BXYaA!EoHBSqP zs#QykqQBhAg8)BjX18cwY_?Stf?`_~Nv>YWu(sh8FXu#`;(^)$~{N=97r9EgnJZglcB1(K}jMTDaB50`9;?*UNZt*~*;DVEq1R6=9 zTe@>R$k&Sb_0Or-N_Hfj&=#1|_frEXh-pVy!o$HUP?cy!JQ@PGui>`RzJKpmUc626 z{u%_3p2VVd&)5^1Hs?S<5<$f9)&VnReG|@0Z>i)j8NJaZStV6OXSBbe`4PHh&Wh** z)tI%NbdN_})s^~@boe;C3j~GTA>354ZmPA!+snV=JZq`!MjAo%^oEz!W4L##cw-KR zOKFMZD&37rD|Mum*H>@&Gme+Dg2UhM(if_0A@~Hf^FKV~CRSN|HAEma6S*C_t;CS_ zQ$QPR#8=>#UcPA~t;a0zL=dPhtPRnjPk^W9pTvB3{MAx&%fs1Q;GmMkP8)Zlet2;X zt`<(5<~9+$JY@KchdW)?hqp!>Duio1B&2P;doy(U?c3cHl3mhCE6-q}`#@1Nv4WS# z7dHMkCTMag?VnGngdK5tCg7xZH`&85|Bd{vFr#44P5@;N-~hY$8tK)R1=~i|dzAFo zJ#y5m9L2Pz+oDb6m*T5~`n?Sanz<5hi$6lO-Aqb@Q#;tT!e2^t4K_9nj$Kh$*3-WR zBHQ1{K1|x-sEA#&cZ5odN+kB>hAl>C+xeFuwk2IXh%R$ zE1g=TD&|G7t`EomT3$ZuueRe|sVWp8(a*qJ;-NM)AM?Dq)}tP-BP67=ns;1U!NEFH z*QO=JMzH#o4R>omuMKje zpbHCGUDvwXtIm+^PPG%*`+>&3eJ@$X=Eg@AFIiMSn{i71q;I#Do1x6bPmCJeP%>Y= zx3pvb)Ta|`)Epp*W>oLK(N-sS4>d}$c}n#|3B<8U7@P(CUikA;8kFIBeMC{+CTX=%=)nRr48B4Z^+ zo!YQ4t5=DocfI-Wwf2dVa<($&wb;#E*nB7n)0=RL$4@synS$WX#zH5>|Hs=LMTYk+ zJg8%G129nasz}z)d+dfFM~YxBKami7l$Y(Y)5r7bl{5rcmkF)sdhG`N5?wg;BQktE zX(eZYa zQgU(353M-=^3Us?ZtTg2H1~%ad5~*n&6#mn1C2xQ*WOCEliEDFpqjd6>*K4;xNp&K z4>Pu&4h@RQBxNzbQN8eh<6xgtV4(XZ{+iA0E92Ge=ZOQE&rG9AUS!qnn0}w)d)r&t zaE3l)HYVx`t`2_@HW^%`&ZQ=^A?Y9C$<(Y9KX<^vkK^+%Q&vS3nti~5w6y9$k=@Aq zuHkp(9GrTZNX#QX)w^-+`coy8TZsrb+OEH?1C5B8i*9H^T1{hp&4@O@@bZTv4$KI9u~HD-Za_#kRgA)#R4qxz#)+&nlZRS;yuP=W zx=^I+>FIkHH&R)LjJ|Yk~1PY0xD^0bPs2h{Eiu#wIQxYPinF3${ z!SipnN#BDyr~Bp0d&Y}~c?=sNpIR3nzzyhUMG=k`;59CJQ)O#3qtXhuN&}aM&$w)WUvpFl`X*6URHBL@?cq@K38_?L6salCVZ!0*E zthbh7gYKGy14C^^Z~oj1aWp&O3~IDld03wCyMt5)x5L!86MEdxN3v#`T~2!@93&Yh zl+EN*_N4^%szry&pUQ65*%oO7%Ifyaue18I7t8fGWP}qMFi9@0kcyR|9VXsIgL7Kx zdOwZuIIP(A3lMBM4uPP|rKBg2-?@;wx5I@8gSg7gTHyK6JnG+-U*Wi$(#{h3>lVKo z!@x))w(&8q5;k7jrzJce(9J=T%8zh{m;r9H?Vmj2jHsb>eBNa3a}&NnKklMlzvO*b zLTnPY00oW_8E*tP&dtr{rP6Ww$9me(dQ2?e#fKH}h3hwe=v<{+yPcewyPB{ZC_9}l zTow9e78ll%#mAK3O?p?@!eLEJ%G>&txU!KII!o6U>ol$oL=VX>0*LYcb~BU~BT~T3m2^#V(R%dV%I0 zBFRK+NM+65^CuL%3?xU{(@8F!F0@y7Hi+Nf5UYo!#4Bpk@6EzVFijaLRv@Hj+1qv_ zKookggFIfV@KF*G5k+A5cv(yB3c7h_NLA@6^C;aA1(r!1EcC+oCFi zyv6RCy6ce{g6dy%wRt`|(Z;L2=$P!2M585wD1zDgr&wj~`rJ z4Tf)+a~ropG7ou93O(F@|KU0jd(z&(y{Lni_KAPRP)Xid3QID`6H0}ti6l9)r+9Ad zo9cK?Zq=p+XC->ND^8;`OqAl6!<71J?{;5JuR_Q6ksXQtZWB;|eM-%rTDCP5cQ)L> zfjjZ1MhtS!!_D9IHVJtOi>W$N`3W3#f>!|_3>n?y}d^owB^SI9lKuzs()Xq>li3HR@6l;=O*!@R|H6q$#m#PC(`!DjTY|* zwnbKR+nE0Jk1vcL$Ra`29JrDpGG?miB5=PNM@$Pwbe#pkib#{3M_}gm)^tU|gK<3~ zte-^}44}2^n|cJzrJkUV1>&PBKmWmbLYae(+%wah_iseQlw&n75GQC{xsvIXXNzKY zDx}>g9;`JGs&ePLm4JArf7N9G>rGB?fU?t~qB`(cnXXdo4pZxt%mC!ODrNA}G73F@l603r#388ob#$t{;*2VaYI$ylbmL|2A@Y0D&=ZhtMAO6RdreF$Wqmw(iHOq|%e16AU^eL5uLfyKAiSm@htdO%yh< zWWy%qZ+7?|0zATfLYwDkl*k0mTOQBh>?f_>TN__sl{l@;W*!5WEp8mCxTvzY zw!1x&zIZ~5&^W<&Dftg@ZD8{N@6;`Rqfx|map@Bo+0nT;?z`xn{DDR+OK8d@K2y@C zCA`_EYI1{WEm|b4xrAOLO*LV-T5ODXKo+G4O{#wSg{76Oj zje%eU8|F1?qVwVYgQG`kw6!p(y~R6sSa1o^5`Sl77C)Og2ExJ{W8@uh%3-i>wz3?!Ed>FgR+<+BGS0om6BB6?%tZxt2DEz8ZML5aP+I$d$!3_thXFy zhxe??0#o{P*fumjf0JTwG722RTE1~8>{cq<)oV}5(uzIZnFt^m6*cQkmMK%jT+BeQ zrC6ov)d=Gb27T4GVCt));cTGZ$Wjp-mDn?Oo?i}E`&X=ofyY#D9a{QZx>l!XlT<%7jlO#ywmjd-cb>ZS$zKuIo;))#SUCL>dk?&cX6G69d_n z?%Md#Vg^QXhShs6ms&Yl`%{(ZbIUv7KQJte>@mvlQ#?*6D$qA2lAaOW z!cD3~=1vG{EV=tM@Xfg!aQbPadVpop6`xm-cjqci7^yFk#E7prMg)fbK=PjPr1Qe( zQ|1H#ZKvv)%!$8U7RrsEW@lMqu_CDqV&1XY)2$B~tacwB>q~-C){X?zVz=wmr_b0d z>hy7~;m}TeOGgeV!ad9rfK2?bm(a<=L$ztv5a>?1fwA>!HdmF;VS`g>`%5r@9*R9i z@}nbCVUFzM@T8%2UkHIolAPLIRlMdk8_=}<$L5o#j}A`$YB?A1HpxslfJ6Vjs-t?U z=tQpAn#IoMP#9?XL7e^xxf>(?n^qUU6pPqh5=-vB*W3`#_~m<1c`lq94yW6VIvx}< z_F8QIHRaveMh~LH)($X?)pio%m8S{RMyN%*t2m~XQ}8cb;-9+KD#QR9?&+G}4Ewh@ zFC)FbFaJey4gSEaLfiBLp}c2aFWKz;@|<3aPgSS(5xgTMTOTs0oo%AP(;C&jY9l=C z`VO6aG~mPxw|@C+LjEhTKY2DC+s{s5(fSt>;MN6%Av>}-x;gIsK(UUsA#09`1jA0o zI@JH7Rn$>BkL+Ip!yY4Tr`epm&`*+rWibHZB4ubcOH-)8s_0K7&|@@kL)8Zc2TLCn z8fk-Nq7`RG-Gy)VIxU+Jb@Wu~N?itvL`|WdBsdM`^+1RwT4Ymn{-@WILrmrMDa2pc zipJ4)0HUA(LiAxl^vrkJx|2;7=qN-(DyO=(EpwK}-5f#%^a9kvn(7F4W;6*{@M+>A z3cWAq>(!AzMheSyk!!H|ugY9G<%SF~Ja_|nTRQBlxeea=Z{-h`K5_+Qkoz;2;T(`0^u&?29YOx zT1!QY*6fpN&ZYms4OpLZw@U4OVloxKs%QKzKu=BjSYdrb4a7;V^|{|^)!rN&PwId4 z^zMTvKl$u)I%5A=L0jwRT01`c-u4|;82aO$v(JRL&iOMneZWgzu95}?^T#x8-cN^B zwkdT^VD2+*ti|e)#{I@zc!oi_Vw*0LGy?pag5m0h6yt8v-I8i>KC5O`YZgywYm%Hu zO6TtMtCSgUZmHqqO5Ax3$cR~nbU@>$RSuaTo9IEi*AQ^dzL?DwGEDasyC=NuwfK_Jhf+0P6GU!c=$`DD;TL_c zZ`4tjnWJA@$WoA+y*>aIOz0CUwv-7;?%Rkq5 zKwI8*e_9=Hir29CkqU2`8BVkpb7CYvbI-!`;z#0_q26RLvpzax-h8^)BBT|p-|x7v zvBtjfaXaR5z;oprvDbriUh2z_q~j&(VQnYWg6~|Iu0y4l1KurU#NIJUz+L?80H~p1 zdX{&z5>QQX?N+N9=;85tl5$qQpV*85%v@X_3gL#dM69g#uh>6go7a__qr2}}B_FG< z__G?w$~`y)DJC}VVX-GE7t3!5;8`~n??cVoN4n}Pp8|1{`*izwc_XB!rg2ofJ$D%H zW%)QMeqnP>n+M5HB>^fC-Ev9xqAi*~8f4|B1UeLiZG!wXC-d`;UKI1m*!1+;CS%@H zJBmfYd}4Q3N$T55wv%+MZ4Qw6-ls_WKK+h#ZVVKM?YV;diwNCrA}X5#TH|BLDRzeud%nEzYf9$=jx{d=3Wm9>*M(~_I=G`Kx_4~)R2>?^6S0QrzwTgWJ`x z5Ejab#yn^HZj31~j~jF@Xq&>{wx(1lQy534U=TdylBGJ!mn02SL>!#GzmCgKHmtq^ z45&VV9{X))%Jd4xn1xMh23l{=0K)`*8x+xDBZX@WXXN+s&@qGJzSGjXXs5JZV%HJw znUV}U?g7}@jcB*Dl7Pu3AEj57>+^ft^wjN}=uM*2$0%sZx<8Mz$1tp=Cf(e;r?pA7 zayIVu5$>>S*C41b4Yn+Zmz?VjLrU&e!}V5BU%+~G_(7ME(XQbZJ}ET`w!RP6r23DJ z^?!c=;A_Kjx1!#NdF&yPdIJotmb%cRKqxzG{uW(KYu$#2pFDrdcMWPl88(6K6B?7Y?dehnuWAQ{XJs5~4^oS9*d`u36-dX0k50=y zd`BDf)2XQ-Dy#>owj8J-rcwSn5MTFLmA6^ z%ecaKp@@*pr|JvcJy$QYyK2Gfvm}Xa1BnGu4`gvb_O9W=gxa>5G)3e#Bx#f2v4x0wpbgn8#44r)z54IKmK3}CBH1zA4`>fjp5P~ue{dXn zAH6fg;nL&?!JGR>`}s367t*D3XJef-*BId`wSGoOj5Gnej6wldMJ>vhPYHG}88%@` zH9Ef=^WnBihG^WTs(I%6c8pL({g;c$bFBWs#TGhfb$?WN$Z!ytn1ipTo5n=$p*}d( zA~ad?KViH0?B8X1P!wNi^H)_-gII#-m;yD3`0&-ur&#}_l04pl6#uIK9a`qalxh&u zQsaC>M$}hb&tf8R{utwrA;+0pOVkxKj3xTWvh>EAVPLn@y8)lyg@P`9o!W(si|>I) z!?$x@kKvw%qV#|5FNalQ=bGS~3;7e>=6F`UPo#;P$acPEKOy6#Dqe{hO&7R+%lY_c z4VlO(NWQ6j>cdWK2|k0{4Ix2E_jY|uA=UcK~953=EfJ^JHf4y8uC?JpeA6%j=Y!#n;?lx?Yb8#Dg4!;oEZ}kuhcd`{E)%5k- z*!1S&y(&7e>~w*M-<{YEM(Ajza(1S6PTfh#wXOp zX<*YTFn3|xDjSOevuceVlKz8hJJ!}*#5`_^`X1oBL`R1TOmcjjKP*<#Aj_-L5O)>{ zC@+kd(@vTcFzu|5Sp$AnbXI9T?FIjy(j6oAKEw_U2)AE-@*LbYyM-L*q+I`u`BQ*0 zRATQ1`W_h?YJ(MgIF|W{Tn|pOYu1gwItxJ(V;EuT}A$?ry6RUJvnt2*M zXPte4O?;I4%Q>rPj>JW?d^0sCF2jn_?X>S;KjGIv#af?QS&*ocIHn-jyMjoVryLFN z>_PE~U&Yy!sjvY3)gpR$h$1e4`DZ)yMv&a8s;5*U$eBkKW7?iWQ=%tDrjrMpZ ztHhB0JlGz^jnGrFXw_1dO8X!I?;JYV^y#O~dLKILG^fpU$07~K2&uL9zCkeM49l3F zAUmY-UI$Mb{mo4S`x8GK^9cFDN%u_aRL zYFyEbcu0_|mtEyu&*QNUTJU%W*Yo#Agqc^O{HG)XP91w5@6W#^568UL&N6W#dJuB9 z5)CX`3HLbH1)sau%@{qjJqQ$D~=xFK$r=kxMN$G#T*AY?&A?`SH4B2km&iV$@%`8Jov~3z^377gqCI7(z zEc=Va;>8O2&Z1O#LS1O&^KJI5HYxPywdA%xxUwv1G4Zd>eGMXi2X)_%SyYU3VpM11 z1tey=<852Ds>a@426Z3hv=rJIUD3t|{45wFvR-!E$n&w^f$**v)UEc98-yMv`Ou%L z)+;;a@M8}sYBVHR^a@4kdeS9X5t=N#WjkWUG(d*;<9I0NT14o0& z=Ow)K(|b%Ngopp2qcbHhg^wl;wU%S=3XaC?rrK%|Y1!$*s+pwH$^vLo_wi<8$SnCq z>(^6;ipe#Bl6Dn~!)pd5N()mN?i!`bB%&wMVO> zNLE3T>BiTap>H(@9TeSY4h7aldaLJ}BYdfvjUl?6&8N+!clTA|>x5?r^vkUIjkCJy z6s>edTtw?@$bYdqQvSi&wkasYIz4HZLYq_~`sGuu< zwSLWFRbG9D&SKS1n~F|--lJbSP{W=Gmyy>Fz~H6h=QN$$V1tZ$(5Cziw2+iEUo|sp zbL=pGd8LtdGUFNVBJYdyBQNyRJc|x!-@3>j;rwO+VE0_XswvA&GJ<$!pDM$oT#PDE z{r&nMT>nzq2xNx73AD&C_^1$WIz-m;#_{Z4^?7Vi&3`s_8*enl`K;R&%l@$%=8qh{ zz4%Ki+O(r6eXHr_Vnh1vX0IPFg!HcJrg!p!`|sD4Zx4;z6pvMvz;j`9pe9?t^2g(} z&d;4~q1$Bp9{wdPN$S|HhyXREMMp=LqEH*O{K0+zY36R2nu<@Hh$lZq6qt6wL0HbM zSa*$SxpnBKtaOb?JrUdqnbYn=JB3#OmU2GFKGk%Wv>WYY@%Flz`QgY3^^jP6CLB?D z^IIUPRH?j_98^z|5I7{`(3LW9m{xYp?zfJ88ZtnCo|rGbpRii7Ta+_TwEd)CIZUD; zUDgwPgZmxDK!Yc8sLOU`QHt}z08=xhez_K%i1Glt+zhKOEez-IT@cU6 zYNl24oIshwZU!D<#OQvcQzoNWZYh-ebDV;N_uv9_0-+e`adr`_?~Qj!{~DZJWSd+G zN$JlMphZX_~`ftS5J$L&3kgCDu&+HM&t0(3rkc#&Pi(_a{e@6voC4&VBV8Z9TW z`qO{b_E8vdN%H#s7*S8hJ|S+yVky}c?o~d$)@fV$qrTFI#Wv$GG0v=S3NO;SO`RM< zyt&C#s06fM{L&AEarj=`GX~$OgbYb&*$;|dfr#{> zWssvF3@!O9vWfF?EiJ8^wL$7XdlmBRZkd;2qcz`O`}fQsa-U4O5@QZL_9m;#zLeVD z@A~~N4CSE6qL$SX*pH^a=b7>6qw$Veqqq$EqF>jX0K-;dj-h1DqBM=DmfFe=Lo1ke(M2yJ)UrL8$zit9db)A8HX~yl?7K zWAp_R*EIc7B?Shh-<9+FX7!WgNs`I!v7-YvjbYmyd6)*A+iyoIY2Y`d0=6QWQ?wn0 z6LR+61aPO$Q9@IBQ)h&{J{=-mSB#bavGlSb@pB)cNXXZuHj{R3g=R1N9LEPr+2{`A zXf|7sq6AOPs@ma5K11S!Q~N_LsF7go*c{Mt(ecI`hg>wNwiJByNzKrS_2#?=@vjQ- zv0n$K51niZWHF-6S_IXhUxZAN)kwK*P>C9xk0p6lma6=N3tU$3A}+?UZ55D2&7gcf zU5J0uA~!)E!=QN$<*`t*RXK9+e1H9+ax%5?BOp3Ad(s9M^Bv*kl_W_|Prw=cN z5UT(`KYRNs==}bL`!(x3`jR~}>X>VW?-8si#rS&-itc*VM&olUaz)h^&tS<$d9kHY zTwl!wPs2~<7^OU?`fv!`TA!G}f^gEl8r7t_x_YO#@QsU4-*o{#3MGzj;yn-WWm09{ zjtIDFM-NMwC1?s<--tkBe|GOG>dFGgaQ+WlZyD6)_eXK!p=fDwE$*~vachC%?(P~a zxDXml_(9gI@_s*T>LMeZ zG@ec*N{_Np(syvMYCP@g+4MLE>H1F;wnX3)wQwH&`adokjPSI~j?*$k;SP6yd8fhx zJrW;r3mNvRl6Vx(V0=vMa-fqY$o4Y(ofAN~MPnr{LJbu2Szz`CF1?UBLFyy#F8Ee{kDMdQ%)LZ(y?z%{SDq>C$e-P74p{Ks$_-m*#|g(U;%(=@^QEDQDTb z2oo($fSD?(Pr@1aM;l6&&^_MOIR1Ibwon0U>d^11lzI(3PC@D|1g;rlx}&w%?I*$t9-9OxAtwItA=?igjt-L|vB0m z{2~xnBY+^~G|0RLSVxK!SiGU8(s;ttjlZ!hGC{y7p+;!>N6ElV;BiG{q!jG`nKYBek%H|M9MWkKGR0;hD zmj@d1>s;*w{U(|h6tFJt@CpTAH^zNK!aQ$}BN1phoN4oAHki>k=&?2+#4yDP=t4OA z7vIijLK3|ju+l;tnYgqf@Nw;gAGg`BWd=#fo)4Wl5xhh*d;Yfw2U+z29-4dpY*M|c zcPi{s|2=GmhL0wTmklsWh}*Q11mx$sk|N;`9O6bRXdxsM&GJlr?cNes-fHb*MQtwQc`Q@DLx)B+R7;FWA+Az|L0-BtJxr!{aIEEGC{?_4U|4RKffXV zft)BkB+$$qL>4n@@4e1r1zdnNtK1Y&dXd696rWP#q0|eV%(4x0w*vB#n__eHVu%hd zYS9-a1%SltCEiJ9H1@%p-&fYBu);Z#Gi`$V-`JPqf34iFr`%a#ZBjxNxo{Xb!%(s3 zMM{{X>mBvqc{LGjQx}W5G{Kk8bCIWw$F6>OR_;9f^RxIbzKx#)xb`MLdnv}MuWB`Lum|vfF`Gm;?@e-k`4UaLc z8hOqjRL-SFBuF8oT64Trsi?~i%YRX9=PRb36~BC5(;WWA!ku&qFLb2E6i`Dg^wy?H zmjX&tW06mA%GAt=NjA$PZdhyz6L(BrDS66hi#ZIU?Dj^Qrt+h0A_?G%>Ht5ktL@Kp zeCM9C5P++zgAe<2D7Xu@rTQn{NhA0S$>2-?-I#6d=A^C^&33StpM2N2zkePqAE89c z$nrPv&eU8euDZ;enyb0e6rDbMl@jWTa-fBD)+#N7=&mI}BfF(l5p=T&)BV;a@smmc zUs&Uz3$55>R&DoDRqIP9nzl~g_~QRQpbP`b4riM4>OJ;Y7L{AnO`GY9XC>t4r@yLF z3~mt4-g*D|SD0;<1uRg?3o{q;V}dT2g9YyN+rgg$g+fGj3HlW^Bt6;Xqn1xGY$YvW39ji$~*!`)ccjH8Asqu-60zbB^R5L;JjTRHnf)_1H;c zIrRJ#9aHtKhrC@(q^z8u2HE9>#+?Yq3`jI7E#yb4fnUWvvDct)AbqeVosu9y%1Lqj zj#sr^ld9MNy5U`8hvkd#+~(Q>LcaftxQayi?BUeqrdr~&s`$p8SaYaX6S{)D$igG} z@;VQf;C0acH45Zc@aUNT6unSg0wCQ6XVG1X*BwWWR_u*# zk%nmu-;rt-KBBz*Y?x&;iBfG!(AJ8-F$!1>(z|hQF3VrK`5M!G{RzF_2xk6$8mTtz z6`k^+v6w^=zTo{2j<>pfr^DHXpcJ@kog6!^EDhbig}LBsM@&6m2H3x@BL%{rp6V(- zx{-2~gO3mf;G`5svu9k?PG3*T+QNB$MsofWm!;4@&5^riPFWOUPFW6gg>N~;oAnVi z5&U7}tGm#Oy7tLa7&7aDrsN}U+YE;SrwWNaIYsflW2I&FvJA&ff<-%3{z}08-_g$h z`xOwNow_m)Nj%SR^R0k=Ji5j-@@vs+PuEgqd27*yy&j*#KRfzYS{|W?_oT2veAWl; zfLEp<4{im&-y%$Te%mOaf<=9>{(*GWf$H!h<-E0JVfv;?q?}w>fJO3(>&x3~?El_w z9o8k#Q%@kp+El8j*`;FMRlZfzKgsO%KL`kY+>L$UU@Q@jpqfNiANk5x~tohvB*peR20J;V0><5hPxJauzqHIzyPDTq~G zLcMRhzP9zjQ^LU~KI519hkC zL(7+)_HJC$Z=XDwBmp)z-Q>UG9}S*11vD+3{)5xUZ$0s0%_~Tn=Bm(5;qAb2P>uNu z8xB;=zM?e`coKIO@4m7XYUWs{-$nimz;`n{6p->8YQq#5Sm?4BOZWn~@{`$dafDdD z%>N@6r~;o*gm?u9A?(bRUKHMFQa&oWzq)_KeuPm~(E4XzB?Kcet8+)!Bis>hx!t_i zO^!IKn@aVauJyh-%-c$(Zfm}_lbZT9+T?_AP+Q2$tgEg|S5_JJxLxXu+Hq&-W`u10 z491`I+!gA|Z++A4Z|i&prs}k>@J(L#Q^b`&TLw6=I+%8ZsdaEx*khQ|e11$8=h_=IbVw~K25taHN?DEnTO`gL9zf~uFf+0rpK>3e9y?XXCy{kp4oDRM}SGM|e zv-kGO^G6=-RtmCL5&^l%@TxKnQs_Sq9|6#Nm&6W5iuC6?D0jT0-dIjjnjE!s<>){_ z$Mfr})-E?{UZPi<`)F?Tf9Sf^S*#7?sm>qr6O2iKl;8S=qyVo6&GwC~ZWr_C=fo>K zt}ADYq8O$W{h9Myn{4Fl>q}|Zqw>(7%9k!m$H#9Fm`5mPPL_eR0cDDMk&q(Gt?B*C zWl>6ldl}T#qnW^__aTotD0<6Or~=;QLx<27na-wC`g&1I_NGz9gQYE;UzX#uKiw{= zPXU}}gz9IO&Y?^b$V1k@t|8c{s)Q-wIG@!c=uBkgrYYG;XrioF+mb?n6qF6{S?COH zt%8y&9edeLA(Z*w@EsR#eIT( z%a)xbH7~2jR9YW{Ll@06>*>DJFCVZ`WbbP|oa^1TK_f4W=ECkdhlFQl#!WGDI*ycL zcm6?jo*AVd{2W~bQ{GRQ+spQw8+9cnF>IVU`0vW>CdULKl>I!fbB$Mp{E|7l^;$`@KT>%nH zAqj$j%3$%`l4A|wCHS?()m=o|0s%0;)4BF@$mlrEN3uxSPf{$<*20ur9oaJ0+hLzv zcy}Na?iO10O~KyfG}N&@-+V>fUrKl`o#o6zi^MvNwssWzi{D*Y>T{$#b}Ff`7Hdu_ z-1j}kJGl3mZp*i|NofjK(Ra0}Y~7A^ndv6s8w6~Kd=ZpMZz9>n>GLjPoRdajusm|d zBGc4<-?$jfCox{w{Y;3VGs_>C-p4j%Z`@)@={O9fUgiF|&h=T5SPBP0Tyh@??4{oC z1T?3?#z68MCJOgS1~hYn_lRiBN!f)IMPj(Bdse!$*r>WBeliGsA z5{dxOAjrX%54}}AgUF=tqx9aj&`1@g`_K9O&CQ-zx4NUTrU!Oy&tekm69anGET6()ESrk~Lk$&$JJj58gX{NHHek=3*q^ zZ=VSd>n6O!A0tsA=wnf~r@mtmXq9OwC>Sqi%3=vFmusk2!)`9`0+{ z@UM|E>->d=cj{^)pYx+Xshs*{tU7z{(|c#f>=-*>`#07B%a$fw9d1U5VcdKnI6&#} z)UF=d#u_IwrK18bp3TYt6X4J1^OfT4lXYT-zov>TM)8>qmSyjTAs%xEAnaWlz4F9fnR^XfvHSXdhJ`T z+12n)$;^0zF!6W!;r@7Vxy{4Cy4RTcyiqHGvH+y=2ZK8jr6;LN@44KxJzGt+F(kU9 ziV>|eh&I*;8IQJj*B}%C7S#03Ti0G$=|`;4{<$3Yd6BxVQr>w#{h0jciRdZ~v(AWmw zM>1a>{lC8!QVPEvzvuB*DWX}mF(1>xy42^Zsomo$l~%=RS#q7BEO103dDW&nwu*0c zI8pZfmcVG(C8iRXR;V}f7FH6tq^|K&P&2M5lEr(B8u2Q30pS&-r}31XkTd5=1~0=6 zQ+WToO4PDnh{KIiz>1e_AvYfTyq4oNnjHCSL-`X^bP5@JrsW-O-LId6S(AEKkqYNF z)+BTeTRljT*!w(@N3$FDh8` z&>ycSdra4%BP>$zv3OaPKyy}Ydws+{oNv@Bi^k-wQqcDxrS1?H?Wg7|;rs$p&!%w-$nr`WWs7Va* zb@0j13riLEFkv;i+-mv@T{N?6;7GP26`?0(y*;mq=0B*l?NCQHewa5XSkoigIyZLo-mJbR6dLRWao{Mzo`(=UnCu8XXb~=AZCLCW- zH!-P5y$pQBzNTvS!KM_ZgnWqxDCZ2-*SLOnHErT?ad8)pBV)7%$msl&iu*qgER8BE z)BjI=S5nfd5~#30W5-D4&*Lm)HGEfXwm#|?nRxCTFqRH5Eg8NmToaN28QP}448=mm zmSf;ei-zyYz0$^c4HO}!zSXMpWyL!`=40ppeBRcMGp$;*)IxC!K5ecqZ)41%Q*WHy z%TH4$RyR3wbJqbqBZW4e)Mwv`0574rz67dJd;-8xXeYshvsb!feBIpNQ9!o!3SDt? zZM(KYIq4^DRK)aK>2Quu{1$P;&`wTnSzAetM>>S#ej~0jq&@=-$)EhV}!w6Yo+AZ7d1a;c~nWE^rZ1mzji$Wer zp;Hkx4rIz%ZXKR*%Vv~yOQ*&gS80_Tr5rKHvdy@@wB5g&b*esdAd7Soyd*8?@{Lh& zWu8GX_W_4-^Tw{EjvW@6llod6kB`=q{Rj5}zivPLebrI37(G)JtE@r}&UU%)8KoqA z$ODhYDPX2p>v?k=Y9?*zTlTXzG|vOOG!@Tg=ft*YQ=lWklq7>p1dge#m`Tn^lT1%t zCMrb*h!RZW%nZ45G<7Ixrgts$M66juX{jx7^VYQ9fqivL>#$Zx6wE2^^&~K3P;p19 zQ9^aa*0VYq1QjZyZfflWob|r{7{dY_N|F4LPRO;SUMQI-SO3`i!92uN<)b^T80%B| zGaM<4rE%i~3IE&vr=T|*BGy8%XhP_Z^7bU_!;{>;?8n^-7gJ9>GiQ1<7isvKGt`Y}QmFiyq ze%>;Nk4$1guiVo|tD&dXe7cVyqyWS7p( zB+`De66r(XqVLMloJzmHK>8y~_*EYstU74aj<359B((n-PB7xEL_rlGEKQ*YKRqEN z9^Y%E#GzmTv?;&4;Fq~X)`$d=#x=dd5UJ<9Yp`Emr(Bxz!h@#5{kJL&b-IgNetk=^ zg}+?0wl&As1DZY($)-4&&m8~3<&4&Cj14L++c<67@WdBt3c$yQ9$OrTeDSiZMpk@_ zDbibBnWBjJnwzab8Hx_?3Pw$bKWHT&G2FD6}?&Aq1TAj`1;%H%$=SAeHU3FL4N&!#1Tgi7Ofl_RPO61~6xS zl+wv%T{iGd>z=1ZJnelwVYJ}%wE80gv&s|=J?I}JJ2q6CW?}z`Mb%6DsF=T zz9>A?7ASh2$YFFXB5!T0dWKG*Uf>-!aZP86-Lv420DM*@dmOvEefnApexInw>X*4f z_GWi%&=(7JJ+^6FBa_@o0C`rqT<#0>bWn1V69V^Y;~$?useq; z2-OK>pH$SlE!!H2`+6!Je(Q&7O-}Z9Nf~HOx+rmw`9t+{x-b)%d~WuX($x={-`;r`j|E= z^5Ee!C38i#>Uodv*bm>z{!_gPL2L;ZV;9DFP@F@KXir#?MVIu}ye7Lp9Onf%P5p*w zs)xFD)X!JZ)g@q4eJPmi5B%sTDJ1q!FD&9!hwF5ijz<|X(Yvuthe3Edr68j7G6jln z^(383Ua4CrDcyx=6@=nN3MPpLp?Pn)m3!?)-4p6E<;}&emy+&A@75^1Lk*oNLw^6;5ahVH-}Oex71Jji77$8Uwm?2T{&u|L#USk61Rw}EDZl}q~ia!v0t zyG*Om`PNbq>&t(IvCSL>H#@|mhmd5K~F zP+p}o$Y^g#O>Sy>s=l!UtQLeGpQ^NQBSv4`4m$S?oV*hpFFaRmlyVblxZ<}evi~r; zAdOxWDO!_tD5vfjPmp3TGw1yh)QdO!O6u4aT3wi#AubA-USuyG=vR+6&DwohgeYwE za<3_SWqlts#L++YYRchCdG>wlg-}|wL!{G$O{e2mVKn&GcI!jW1Ly0JvBcB#TkL3s zi5+im-vT?gElJL4OTM>XHG&B|`mN$EBHx5;m-8-}!Nmt>L5f#sD@}Q&P1%28z3)%L zMn(mQa5yXF25$)qB(?&8_$_~&1OBZpX+Bs}VN!T`{+;@1w9(;RDV<4qQN26Xe7+9a z14|IeXib8No&!;@h>U3$yviT+X?XPn^J^t6?O3WR`R{2Q30QDwiqj@h2&T>ZKL}_Q zQL1&NUy7el5ew8UB$ha*!4RR!@-7q1fB2xp-uq{@hF`-+jWPB+Gg`Tywu4L$h<2~4 z4}Z;Du%HjO+#__Ps?NHiN3|GA&H>N!uhnW3+e9MQMGZgeLZ`Pjc@M8E z>E(s&?aHlf^&YtAIli%>(iamas?HaN;+nPoxp4SXCJ1YrRQJRTjoJ~g9Z1<7@Fn_aN0FQU~RQ!tkwQ0PR6iXJ$M4#%JLWg*jm_b(OPTi4_d zu$pe>e{eAEw`RZ>0X>%QVn@I)l-E&lcTms%fyxP}n{+c3Nu(G_+>VpX6mN7$&gUBAX0 zv&rbyfKF&%@>9}toPH;roa&Mrsi@4T!dv~nJnGEZ^WD2!i$C=4YhYw8x_3jC9w!@8X?lnno&vziR>tMMhW4rXpoi_&eS9QgZZ^KHLbb=>_2uj zBlw%7ZLh!_#c#{jAY{kQt_Ow_Q}BG&%<{PBN$e*uEgL0QRLrtXFOIjfL@qo|HQ#qa zs&_E#3@5?D?@vE+vO^>OU|}vF{G4(h>*UIDe(CrBF3+`_5DnmVY8C->AtCI z7GIR<0+A32!y9fiomVyp@Wj}pQ?SI z@G5*^o1;GYD!|#eRQI?|O$e224Nfn|o&?|@VUA7uydT8XJAx`EaEh)Ex*kD)Nio_` zdM6tHV{lQXi!~UmuKXw3jf4GNoh$wBy%iNGFW61{>nEI#|NYeOz=nOysz=xrV}i;N zE|mv0Jk_TFr{gW!&#cfyQ~AH}a{@<%*ZpL!8&bbkR0xsq^h@5kaJ`eRwOjpN6*sw| zYD*9&feSGc%gh$4sJX)1-+BCfPnW$u63{D|#Lf)<^Q;MeB(^3|X^9~%W48y82m8gi z-RR1@VnkkZa#F%!VEw9IV>P=xc7=egW*t-o`rX~GJScRUtqZgdctWUIL+x-9kj>!# zgZqpEeXteYRcxQB$!qG4HOs@Pi}N_brjVI$ZftLv`_SB+B3h~)$;hibmt*t9VpgIe zgTKJE8L=8{!`}XGW38*C^}%aq@@Ydmwv8_zd2W6UqXk6c z$aPR)HL;)zU4dlV)M9ECbehU?`idOML^m}r}dQs z8~s1=Yg+E;qyK80_7M_v?q^!hUHhC8<*zFe@y2BM*-8Vyi+jeDfajcSL>eO(Asjuf z^?p}G=2oaCK8JE3rs%bH?7#)eS6mQA^Fb|{=!+Xddxjs@67-5g|J#N*4>VRVHm)`L zlZc8i1Q6mQQf&AbWEd#hk_TREmHHh^XxdKUud28bMmc0Jr4esVLQr;_mxf`Y_|0x| zedBJ{10+@3cBuey=N?y{u$R8pa{dpFVLA2@-`e6Y%jfL@;@Fh}&W?SFTEjoWJ0EU` zrbYM-7Kiz;tj?}qhtd%4M_>;<8dq&KL4N@Ze<{61#T{5jdHr;Uh;ynm=lW3f-_irx z6%OoO=$5VQKstG{^{zhoC`nRF#BMA{el~}~v>)Zu^vP;21F77PiPjfhN7}<6s955& zdKDc~XE&Ix?c)#>n-3|NLg8-VM}c)SIe%NdZi<9fbLBDlZ^v>i)8iJ9n(!17f6VCW z>q3`pFz-oT_|&o9Ql?>j$e9{r@j1Qm15Z=ag9*upl^rA{!I?sP-VxsO5$=UY8+cM- z&pj}}M?<1Gy`I5}5a(DQ3%sa-dEMWtXb-vOeN}Ag1gE=LDrnmNz0m58&iwTO`8l$* z0A>l|@Aj~_-`hCSoJNZQn(cmpKTW@(rb*7At74q|eP+1E+KeDc|Ap1Ec4X>5ID;C! zwxMh}OP1ePxbeF1;+^xYv=#o$1EL6mSaB4#tV<&#tL4c(55+i zp2$0Ia9jox@Z2vdjg%~RiFhI@bJU0K;lGLSpK|{(*3Dw4Q5jB&3sV=&q`C&o5>@&U zZ1$}*6}g!WxHCi$TapHLwi_|lw5sJELs+>qUSKjpV*>B54(g9e2Jd7&_pn?n+S#o> z-C;km*OVOp06nRyc;$gq22(uEzdmO zcM?JWby&>gkCZ3;*MSa|o|^ldA4&6bzcJ|Rl7q2Qm)SYHMl{x-qqEeUW`alk4)YZLiRMTC z5!_S^b*LoK2{Wk%c?<>%y|nhz+k1|adI_VNy>1jrh_NpfMRTLf1zy_U-zwg_ZaYF( z(x9!Q^a}x7+p@1Ti6lR9f^vG|{A3PU&#S+dSf*dVx^%>eOpzKu(`XkR%)4V>F}^f4 zMv^Qmr|GyyeZrQ@sg}~Yr%YAKRBLtpZ8z8?R_Q^Yd1)k@q1!RyM5K*mO8Yss^ZXre zd+2gS9dl&tJy~DXtI*9`|_TU;8G2dvwwTh^>5l70(pl4t39+F@28b3w9Dc7H2zy+-&HYrs+=Et8B5= z1A(D!0w6>^qUTFYkDsy*NQR%j&W14)7}ihn7`$oyc8WV-u7J?wmCd&+s1|cMtCnOm z9Dv1(KA{}DgB_kP+Tf{)=hSmgch2M77;)+f zvW((chUvENCP}e!Ks0=MyfA@6ZY=Nav=R1D-RD96!BtOZ{WddFJ3F=XqW9XaPbnA7 zr+GBa<*7GV7q(vNWNJnDas{Jje@lN8j1SmnnmG*$yyMx8V?WCx=Gf`wf1Zi%Mp!RPYymT#2T8Cj-yh5G>S+l-i zqTkrVW~zrHu@4~%zcEWxX@UdZPM$@n;2$)vi&lh?y}EiIIPTA$PBypY#>fX-Tnv`H z)-P-Nts7yd&y?-VP|^m{fNUp&*?=R4o%G!Hh=r7%0yu0L9fqoL@&83P(R3Jc5nx3m z|67RMQ#Sns^r!mBpyxUfYY`neG_q1ICF^KpR$8K5Pl<d7PG z%(KVlRU#(G3~%k!CLG9PT=L$s%F4ATFh54dbThkg^GmVVp|MlQTnOqFRjap(FjnhH zP02h(n_H_^pWX9-D^#?&t7JCO>iHy&Q>t*Uz*Q9J)Yzj98ef$a*j;z=(0K;FHfmDw zY+v0s=D0~c@2S5iM({u5B#=p2Kp!=~#l5Ii;A2xIPO_tyKAA3^Q$7axIs#U?UZemq zTgeXN8j^LTT}2+276abmmEKXN*`3U6+=xxE$><^-Jx5J=7|n)%f-YhRAkgVlr;BXv z6G8guew~9;ENn}Sh!t8tB~w993TDpvpg&z&9CeUf1@cy}P1(?|%#A$|k}&xdoIpi5 zJjwK)vx5>y>EK7O!V3M7llD8bQFsc**jrc}5?b4lI5yM`8x(K!g}$5X%Yrgo8TcLf zO(8szDel+jiJ&GFfY)jM}B@*)uQoAen|*^iKC!UzFguqc{WybMPFNGQFFaU+Yo z&?A1|xvNDyu#l1Jk6H*Xi=$IcU+1@DuaI>67RVCMVH$x*3P?{Xl$$Eu<0`@{%6a+TtGIl480y(ag9||a%fF49o2Ype{K0ddByt4I*EUoN3+r>Ot z5+}Z9arCGgNR9y~-S)Dxt_+s9V@Y*o^8{=ZQXW1ICb9O71gvffRRqq`d%jZctQN-< zfHffM!(T|hk)4)Y@dSBSh?$Z{Sz@FMx}Dy;N2InKx;cX4-xX}ZI2FO2Hj3%@ZIF$s z_n)f!8ICDoL_0Ay4~C%&I}b)yVtwVnp)<=Tv?#gu8xu6>p+W0EeZ|&jb)bM*-B zl$ey`&lE1C%%o25z7=69^pJS-kS^6>k(n+(_99vxr84HO=!+s{38q>dyTudxT_I-r z0ra-%Qu+jD@fjyBu`q*RFLikwS?iaJq-&sJlo~FS8%d8sbmjq*R*s+w$yTE5Zv28NVd}UO{7oGZ;tp`*xd4(gVUmZPI1t$ zQHFK!q-Q3L070ma4*q7glp;oI8=d6OtL2Ux7&VB3oyd^HaTcR=suT&$vrP+<$BClC zVy3Y^C9pQH%lsE_qlB4&+%9}{cacTvrb45$W8j{_L#J=|9VS-dm|h=<2>y7@;eygH$wIC&66;BJlxg^{KwuUYh-;& ziUdy5YLCD^^%V@CDVwJ2lqURr_M*E^kQJj0=L70boUPg?s?p{yXTL4=nw>1+^LIMy z=xYhwF&vjPEEK$b>i9J{f_FqUZh>wNeU=bpDyvoM0~)3;d}NZS-0tVn?mNtMEnlgm zNcV?0X#!zicvH|ZhC_9*uS|s*Z=b1mbJ;rP+mQxV)u(X(*F_jX=WzbAYRm6?| z@u*<{KB89`ic&1iW@1u#NL^ZSZN1oF#}&Ussom`bcS=b(FnEB}MdJ|kacT*zh^vYvk^h>) zyXOo(QMTt_W_39~e$I@GZf#X0SIa;vaT0aLy~R6*MNBXU2b2D;(WMFMQG8WOwK=Rq z1aPIh5KBP9mJed=34hIaPT-RuI}!vGJPf{6x-NxF3Dzxa*u@+ zX*jDy>DYG{PLvQxb8~kMP8jJ8Zu=^p;kO|vHQF?zjH*mE^B(()jMVVXUb7L9Vi3bJ zP7=7+r}*wjRgl3BvEd%-hj5X5Q{D89x?-&p_Z8|Rw{FXDyGX528h{laea-39g4T+k zR$)1xGp%clUxK6>1*`g^>g1hsZ;y%>C~`8~=fwAPy2Amc;RSQawlkZDO1Wz|?C=uu z2|eMt_gydB{H>~L4m+Dw2&A};YWM#h1XlQ0(~UUOVr^vZF$2;mTzHdbcf~#7qjAh; zxST(qOfv^rli*n;x12tRP0dz$_J(?Ur+nt5W<1P>%y~q;Sa|!ptSjf&he}g}zh@Bk zUw-p83d*Shxoc>C9_hNjrjLt(!sX0iXs*oa)hauf89{_p$iB*4`GwtvbZ1~%Y5CI- zIXY$Y-{U!Ghc4+$kkywDenNuxAVfsuKGd;@_d&&XIQR*rsW8IsYuEMmoI(ElB-?0Y zp+2>rx!@-ClNF@0D*JbT5$LKJMGy}hF$g2W)Orjmi;6+J!wC5qnM-;#NAAaTaL|oE z7B8qx78H5t+NolD&J8QhWU`c!kRpPLGtpiY_ZE>UnCLDgZHw9X7VUk~8)_yg2(HB# zG`U`-OOS2~dp}0M?=G)l`xM@~f2KN#^c|ngcfR#3$lbFdG3=KO zP(&@jbC*dU*@+Z5`lL+aQ&_WJt%H69D;NGl2Jo9Kc`-PeN~CfSzMDSjZ{u>3*SaH< z)o9F-N?!rcHenTP)C!@tA^zeR>UH_djRVHRaEo8vYP+zN}f9T5AN#vH)L8 zE5RPhP)Lsu38(k0EG;XFE@{nZ1uwy$&Nv6>%aETCfQ6eoDVCtrdLqQwBK511@Vg3BjQelaeQTubq088ZakhDn`oL0;nxAcR4qamu zi9GX?u}0=Y(ty=S!zFH7a;u5oG%}ZNRwLK3#=S)zqq{<?^$c z-iuqc)F6SfP3jM&`cQOlP5FF6e-bQ@VKQmBo5;fvM)(;CO-XGI$9#}80{Via?9Fl^nN9vjTfGf4g(J6oB2?%GCL{k2cISaYsvrrLHh z$Bt6t*QZJ;rzhd*=u3RK|AuUG#xcbuZ$Da!LUX2Aq$!t2&DUFk0koSMG0uawfs!-{vpuWwG76<@e!qrprNos<;9riib&e^Ds)>29BJ z)QHBfbDw$7mMBvTPTu!Uby==)snFi8Yh}bOlJLN!3mocq5@r9RH^3GNKiEB1qO?f8w?hn_p_Ivp9<(xtB z(_ZtEEpsl9>MZ}N3;dnx%#Bcd%Rxh&@-4=DE%)51i&vj=I5WD-3NMrP0p=F!ZSnuM zImZVNDLnt|xgMI?#%k$m#`L zWMe9p%9F;0NFwFPM4oxZOVR%hEzjSZQC6{0bebzaqF3NAX&%q|{DvUsHLLXf-g}pn zLJkHJMQuo2ksf3DiB?1K_qSyZMd0yA|lq%^-*YPRI zC}#*F9_6|6or2oYh7agdHcR0WCx(|_{oKG`dmtn0TJT8;s;uM$Nj)Ikdb1(%Xx5*M z&Wm$V;pk2_h!@$h$aDfTrX0WLe4n0s@mzU0a&?xS~Iw!$vJB5%7=Q-uzHJbBzj>~yX%h8%lHGKKDBTkAxdvDei z+-b1c220nSGrHO*n%btlFYkDX%7I>5g(WJ5h8)(yp+0FhYln|9`i)9rmee-U=>_!9 z56|gsVQ*-v*`Ua>Gq8=aO7&WsevEZd+SNziGh_~9K^lA(_=gHNS^nivNVqifcjIhk zajoDwV2dbC&stY#ebN*83d#Q}q=hYO;%8UKV52{4ol5+K5x`O&Mo%F2MNbcz80q~X z_t0bZ_2h`zczqgMHL=Nc0V85ImQ>5Jk^$=|bidcti5T9$f*JnFq7|s9*w&iJDNoaK z+&MDnD_z3qQoj9-&?&(W zW&rSL^hCsnU1$Tc0h+^^ICBNbDkW{1Jfj^)$J8dujSqEqrf*qEe$EMsSXXV@e1v{{ zVPMB**JY_D#lrGdweQd@FdP%=JMy>D#7VZ!mh&HUisSck!yEOqIlYO_H04&9v+F?P zN3cyOw)JpU2B&x0-MxUdjcH|^oZZ{`{cuj32!x4)TU~=#9pfTwJgsV8Av#R+=p0V|0ViALmqU@8 zvG+%cZMFSb^Rtov;Cv!a$c4M^)~pv|9JV{DWaT+Xnp@no{|pcYbbwoK?`nPknEpiY zmg$ThsFx}iCN}SQWTxA-ZqL3ym69kX`HhJ^X+p38*5^CuiL`ScfS)lWS}fh*sR2!j zx7C_Z9jPUsAN-}tr2hONXYBfS42uN-zO$_GU@HZ^Iw?$RhkK8v1Z-}$m1$ek?4*7N zJ@SQ%v-4;^^>|s_5RhiqxYdgg`Cm*r3n)4@S(U$y`TEIbmfnj9SN_tos;j-_orfDU zbDUT6p@vDD>k;SUOq8LGNAtPTAwGE@SrkuO1(YgOuBNU=^%5SS8qm4bZk&| z`G_~i8rHVRonJ9)+d36hLippSxASdLp+OSlS$PK;S6TG`Z++0aho$-{SnsMsTi3Px z3UjLHkePl+GH?yyCK1CxWfMd@;5is2K!yRnFH4T71NlZd@#SIKt@Mjm46Kx5{ zemW3Is}XsOIP~jdbq2x`9TJ4IcgyFiUI3K>3LK0tGOkDK|wzno!VY$wb@V3;hOA$T_)wqIqmv+ zGQ66oEmvis&M4=qYQzXs z&BE~bS$uhP;W?yVct%+cfOJ3MB$MV_ks=(}$vmKXHr)tQwis?m6C0Q?_b!Y$)|~>P zHR+;Z<2F^IDZ@C;GMJK_Awz8VeBvU`R^M)6kpsx$vUwRW^B<2&0Mu63TD_Auw`i5j zK@bK40<3VOANI>u^wafLsRzSLqEo&w^cvbs&*uhu%j%|yhiPiP_Rd9vv7heBJ$Pqg zI}-gw{{G<=SSHeW4`Yk3TDQJZFpH%628|BPjed7IB~gZ((iD>SGAN*0((_1E2cu?R z&#lX1b_b`xw0tNRCfghhn%{0KOE7zVy|D{tN-l5}AmK*|V%95J-HFr9B+we( zY>d8Iay!+fm%H@Zkh0la#gQ8?gG8E33tC1m48>PiH|Q=~rDsKT#5AUv(h}B9@##5Y zc|U84?6gqMKq`0_{J8V}u$@IGW1zxHLiOv%thX6&xQg7Gd2QrdO7EEs9xe9o)@7w( zwEn}hiC*3#QEK{tjaqJ2o_{hOwziMNME;Wt7eZneLZ|cGmTmg<1J~A}#*VIV=n@Zs z!E(2Uc=6l10_&Q3jSjf|AgWbeuBI|3qb@?%i*>1EJ=gj+gT-Z4hjbW1&6PPsx^*_n zmy7qwrQ+0=sQQA{JaYXHgS#GrVo7tSrS8xq3W_M-|0KUoiXAfw>lxFz-IS{@9H{b* zM@sZW$Z7%q7FuLcfeuyV3n$i9f3Jyu{eFIlyuMme52-ktot5|dKPY?4s5Zj(-4_Zi z6o&%ErBK}6tvJQ4xD`!tcPkdGNN{O!3&8>eDelFB6?b=cy7TUH-gEZ)uk+=6NHR0) z$*d%kHFM8%U)S$4`&7U@tJx$gS0*2@zTX%#@E{I5O`0v9{>)t`hr-K(<>XX)s5utw ziX;Kut&U7`94id^^mY8^yYE$rl;qUTgAO7sa^NXg`K#IaBc~HK-_<>(ne)raGsaEF z`KcG8;eQ5+ux*|+Z-uoq)+cyLXyn!y`vJGW9h)nNGCQWk{?aG0tL6P)GKS;{F|A4= z@*pQkDM^v58Xq71o196vx)v3cBX?M{o55mWkhRxYUQtZY$p_sA)LQo3JJNgC}hw&Yz zID?5Wh`=jLuQuPvhy-6B76_Y=>J-7~Q(@JRdLs`$pUjV(zV=qxXJU8;ear6Sb??RY2c^jYk-f;ja~K0 z$M^E2Gdgs{*XHO?^~SX$<+Bz0!;kmDNfkw95CB^FuQCTOKX-*)AAlO$+VRJnQzTpQ zz(juPUUGj??}l{sMisl0s)A;_iLE!^uAU+^&gB-zOXi)`teP`kp-E}pJtM+teOlbz z0R^<3&PN$slEg$M7HWL^W4UQScDt0-Av!kBcKsRNoGE^VTE^EcTaMx^Q-`!e41z;d z@~@51AnktYp$HWOuEdX9zb#V>>>8F`ao#-K`#xWxfR00uumy~}cRFm_1c$*+3INk5Kfd_=8Q7RQomfxR;r+$pSc6OUOe9!t$X!+I+XVcWE;$TkTl0OaN z`>}n4qx&s(2pY+^tE)c0=5Lw(THgz@rz#aEtr%9@j@ohV?t&F%FntmxaPDO!!A7-b zCz+luX*YQv>eIX*qY0l@AyA*rnd8#e*nL~MM&hD=v*Y2OBSsK{{l;3p^^#mGwt-q9 zy3!Ir`&I+k`}J*|sQ~zS?w*n_J(Af}l9R2dT6*(CW@-4xvCTYT{=ESOxZ|crih1r= zX4=#;4J2Wj5OHyAHwl`o;o0M~(bRzijGWyI2qrm59b0u;4|-&;+)$}wI+SY#c)Ds&1<#O0MDYqpr^&$o-eB83cYayIc)weporNFLMuaddXgj}OJ&w@}m zSx*Qfoc@K#x4}fCdV9(lV^bKf=}spf=U4J#-?_kw9;q_b{9jiSwCL@&DUZXUDV=GC zc>w+T_wTQhbdpOc>#+Tru?k2kf~GQ09od*|h~70ZcZzQzt9?Zd?RwKfu1+bQmR)N2 zr6wL6>pV0({B}&dGHR;0eU`1D)v7SRA}IEEsygg*a3N$hgpFYOut+39Pde;zLXn#3^W0QZMdm z?@{Iz?)2`((RJf)9F2;egg3~Phw2K@m?JB#&&?F17LP3&Fzr zE5%*JJyolOSAAnkbLNLcUoRn)S?HqF^qR?~%wEVQ`;-LelxNXM_Ae`jqKF5oKAl8i zSx*&VyG&994^h7x+UJDpajXJtL1D+gz~*_aR4dlU1(F-G7E( zN{d$P7cN#7suNKOisV3Hhog^Nqq2xonFjR$2H&{-Al~bZKyCO=lA)$*@lO=K14niwrb9KtNyKd3Q#lXQ zC?UF+9i@Fk19IX<81^581SBtb7M6>Urtp5w+F8qIM;fG5Q)4YYr@}hhx~!)ZKa4tG zGrN=D9olsBLPWLbvn{7s3B`_jKU(g5mfn^HdTm`e0LyMF7o0K)51WneeT{<=EH5yt zGj9LxcB`erGY zB*y53-c;{C^F;EFUR=mx!L~FaOzuW}&sU9QZu?0iyK$S}w3)APk9D#kF|z4B5X=vk z$+(Y++r1by_gVeaI00okK3Y+-^K}IpGwCk1XA6+cj(^av|tD=_c62lz>abtjj%^GBJ|`;{v;fHgrE})IDR|??1Pu zmW}61bjZp0D*85LklL~m(3k-wE|3cS$`#8y?H#n`2ZO%ovNU@WB_gYof2M06_eIF4B}*RkdK{~`Tw zTz!6UfY~?|ecK$}|CLkYen_8?U`Dclm?`}Z!17DTM0s)yRYQ*pc-rmXK4qpm9g>`j-wDVs-`jt>l60W<%79aw-kE{=7 zZY#vD@r!!*Nh;-4*|{SPac)Wnst$JoCzI@+iX7L-7Hq9l%ot9n@tt83@n4#L$eY_+ znM4@bBW+O^E0o&nw-hB(uEtJs^_1-4G__Uh)q;~F{dlKmxVW&LvA zv%icL7;Empov1?z?n`oGg7mGu!(J#bQ-@sL|7iNMmi8!%ZI)GdZsxqMKWN#rS*_Nt46p4-)YYm$g=Oa$I*&SDT9=LN;z8u zo%;{m2%l=%nA;hW?EwCm6UeHRmhf9F;?Zzm$dgI zCab^MxMP}UWTT+mzsT2|UU}wHkwR=@9bTQ%S3hQ4?*+5z&zZYiyIhH9&y@JWlR*lM z^nFSZfm`i3P?l0VbPm4DDaZyZFqcem;|ca= zysX4i`PgP^RHSW`hIP(`5+w3~vALBTtPuYrc{z-cz<2%ViQ_O1Upn z{6)~Xw?vp_ohz-amSB!q<1q9J`2Lx)5^IwL=u)}B@AI{T#nF9v@!rS^-pt4RKCf;X zfh0yJ^}zv@r7JL{SugSG--U#n3#H$7ALDWQN!g09&JO_jwGDw17owHSE6kh13P`T~ zl3+VCfXGbe^UhDi#onhof89(v&E`u0yM)5ZBZYSNTn>cZx4op5GN~cqR#9oR;lom$ zdXv{Y{&a{==y1-%i8!l!XC94FptDB%wAF=bUxNmXl+g*3>B=y36BQ+J!zNk5@<@fk zb$X|2U_HOSm&7*|SH4pc?9q1deiH9Ym-ru2=JMggrpcbBw5_!(b0=y84tI#!QPN@P z-K=2z=}zRTw1EXP=Z&9}{vhim*9*vPs<-93y+tZ3{F^QYZdxW%5K(5?xJ033elV-C zYJ6)BP9A7H?oZ8i0RprHFdBPYT1X&nGo0<0PpPPLNQ)cf`uOQ#&Uurb=Pqk!)k>rm z^+?DmsCI%o=C=dF1hZm{<3zrY) z{8dHe5?|y-@E7TRRY*|YmHHRYv%R0KHDPfn66k;OL0H#{P1`trY0J8^f-U`Q>Wj@( z{V9?}eN}EFeVout{q+UQh@*NpoEu^@HXFOT#)T{BHYwaVaFTl@uNDywye|YkEh`3X zBPt9)OCL^#^?N&d~9X^%|zs!8(zfdz^C&T~E9E+!{uqV2k{zYJ|!@o*D` zTBV-r)pC^j-QQcv$UurcsL&9#++uKd;n`?jVui7IdtVM*6_%J&<+a%u$XaoB{X6Aj z4|^&>9~)BO<_}-Un`(k;mO98-*3Ri2Wd<-Qj))Iz1%G!kRbKl%sRn5_qEbY(o;&}~ z*oyxyEAK$HUy@f1_W_yH2uJ>QIhUOBCuQ7r+QZKlatIF)p(gM@Q^^Rk5YSLsMe2>K z+($xm4d3EZC6&BXL~;9>)SU7LVb+tNQT%addY~k+$DGIeWZBw5fV(Ok#$Ep~CthJc z>5xWXxP)YhKp`EuKeJ{5ve;>le2J4b$UkaT?$l~NPrmSj(PA8hv3IKd*Mj3U&(R`| z`2fqa5x_wl1&c4gmBU~7H*^P-BlHOy1l2Q*kAC?Z%?p-PoZHrOA||Ao*sex=Q<-Li zte)gT5I#mr0vyf1)L`XUk^D4!v?q*)1V^O+P3uc_*g;be-qh*0Eu{cy8{mO%Tfd&< zSn(NdWCKDjzG$jYba1{j?nY#gIQ$0Jd91D6aQDR@(U%C+9br1z^13+rx;%}2Hx925 zZYNx2Gc6iYHhU+oVhs0;g`vh)C?f44-@D$=iB=7{0&IzLkEe`BlGnU6xFo^miwE8} z_v%pN&;D#r2l?%61xO@Hxz(Djv|xOgw6~6E`HI!ml6Po%S-T-g40Dd#af0SIT6nilzj!wG{<7QOU-**0{OBm&B zG8p;BVabDJ5_){P^vvpPG~JLZ(6>GV7wvn`J+Li2f+d@2E)J{EFkVnUCs;T#TX>Gd zq}{?^bSdJ(yr#$>uIn{-nQ`!+R6F*ZGdjVm)FS6if;%=G8}6L*tJGTCJ7E$VTaUTC z0v$Q`Z8E@Vo9+u+mb5^ll$K88^>=id>IjHp4eK(qPFui(fZ)^N_ve$ ziQI_BjeFD~z`#3E3-082ywkjB?TcE#FD#$T12mdS8(%jLs;pQXaxZVs%_~@SXh?f) zP)H$`ESl%0h}rD%_;;tBbp32<)?QK{LEVhyooQhI(0zf;a)M5ucx+df%Im~}KDcH1 z>s-fMf_jb)ID4=qTU%A}xk?@D4X%@LSsV8TW}v9@q{chGq#iY=rtfh4dYzfKq;Jj=#Uq%W< zu5d1=2E0m4uBwOrm?1roB8gNJN6N{EYW_p!hN`w|-Gt*+Ji_0un=u9-bGmX1U(plL^0XbTdrBHu>8Hym>pyZsbNFUe%)4XD)|>2?mBmjFp;YxT zVkK==4%+8iJ-?j0jROI& zNl$iMgR_@x$BLyp;r~8-%FX8;EApN?0!#I7qwF?++j{y4!cGY9aQC;{!AV- zdC~xT9y+d(u?+^g`ykIxMpInolX<`){)vX3O`-hJPKE6+GxbxaE?*e4 zynpUb<9^a<16V`$TWlBTXW?s{L(w}Q6FZb2Do84(*LF>_RSydgmcOBReyzed>(Woj zv)7mg*D6s4g__;Z>oYniPZcYnm4?z3N!ii=kY-uqk}h!&G6u9=Q%5nawm7qotve+R zKq=SoCOB-CS*8@q;pvR?X_UO`EF)A7UsBmk7`eBMKx?mA26;A_{a??t@Hczk`>^H(q2v(lEW8>S8#l~<{s0Eg(e5e*Id8{nL#G|Y0rOxyc{eSYG{0d~_ zakN4INrg-&@st2k=rhEABCcDtzny)E&yjs=9UA(TF*GUP)%ZvxveFq(amBG!alvSN z%Sz}PB8jOiWH>vZpceaJRX(Cc9M*bju_AQVbmOb!F?hnk_Vux@4lih5T-1&G4tRd- zgp@Fk^N~kjt%rn!1QMuDDo2@@`+EBFLr?UIpqAo*@R%^d%M<{Zd7A@f{)?zm0e!nBZ;i+g6^%#wu7a%-RfzYP~Jp-Yy;wf-xzj8SlS# z4?U2nsN6Zp4{=rdQ(eP;`bf-a8=RbSkc|yfIQ{V3ZMr{U-Q9<$eQ-$UY#V!Q;l4>N z_PJq3fUs>^Ty59U`)B4j#)L*>5RT1WfMADBN1iCAp8<7!fZc!YH9xb*bvNRXVKO|pddfYMCr>fD`R4E4^s8L$iMJV+rgFw?NZN=e| z4{=+?f$_6zE)G2IhGeo?mSY1(m%ZdXV)<>j)Wra?JoJTNI283bxik?D?b*Ht3}mr$ z>Ls+FjvZgC7pXJ-E-ia;e8O-qbGgY|g?2~IjS_&3BUa(pY1X5(d9<3Sjyf+KAH z`fATdFUZGFZyh_9g6;OzF@476-SsLd5b8qC-jQY{E5~YV9S`AsquZ(Oq7NZ=r@CTS zraqdGGIyqv1Mtim{Wj-AX!qSEyOv*2=Z`=VLOz zXyXOirtxeS&?~cK*~#j4(J9RJ$M>1Lt6bUh8}jg!#AXC{=`6LfF{#aq3H^Rwok_%f z)Uj)QR8Q_T-($*{UFM&0gmDJz@akm)gsKuLFP+d#tUbumB9$EsYr82vv3k>9cHv{X0Trl@ypq5nbj>g z<4LrF>mxh8c+G2_X^+Kt0a=wA0(sQqrME~{!jvtu{LDIc#qV#i`SdmSWqWvn2-kXc zShz$n^dIL3Q1vg2)#z}Zb2Jp?Q5xL+I)l009Klq|Qf2C~?b?jl-@&h_CtP<}~#iXv_yeQ;2< z78!EtLZ>`i)nEv5 zG1&tymo+LJPw{$ysGZbu;r65T4rk1~lUw>j@mR4h`{@0p^^dJQ5T1_+NNmm^a2>O; zJz14!DzI>^_cIU~6=i8w6V6XtE|AmW{|tWb8fShUw@VkNpJW>EDX{(C>-NOEJD^s% zD1F(TUc7lP-jK`->R#kqs191=F_$2u*eo?GFP>t9Kt&T7`sc=eU@z*|TvsP5pIt8S zZ{^X}W}p|oVM17Cz*c$4glDO)1X&){Z4ZH)xrUl6t9Ne)9Q;;F1LzH$VhoV6AECQf zRj;Qe@L@}Hy zu3DebBmC6;In$rs2`Xz^c~YF+$MSt6HERCQ%5dHf`|wRL8S+?B_@FB;s?Y*xmA5Nw z4pVxAs>SLH#HGP=ogmvgb#CLgcK-;S4R^oC4v&lI6{`bS-<-z9zcy7+tDyYhqm+he{gu_2xuJI~k1YSnG`0^9y zmiJWH1u=U}(bY9~E753<*oylchXubg9T{F*EIkf9G^v!Bn;2hcZdL+wAcUbQVZ%H7 zm_|k;OlZl`YAm;5Yzx%UUNOEX^s$&NRk2|>Q{mwzX5aZ^DFu75Z_0-i>$(4i?+Ev^ zkXo^xzmv^$qHi{eCj0U^d`E|=H{58A=dYGdEdso{aHz_8`Ha~+mpWYzwO*arX7`8% zdmA+KjBaOge3i{6r4Jt**d70-?^?0fLL6HBJ-LscwWdQdV=G8vCVfpX?(kNNVUs#n zqSKG_k1IlWCwiZDbKtXhyB85kB1FIW1UM*_iM=gGUCk1E92Q~lMT@EWVKz9Mwj*Tp zTEo3*8fD32r}(TfC$U_f@vGwCcCPdQ6=>3DPP4tsDtypmjJu+*gK64wJi26m4{^EQ z6K_7%FZ|t{OEt8OjZulCW9@>&<(fBBxhd-D{MP>Nb+L84dtL}u3IZI>YZ~V=EtwS9 zZ{MCGoFCzaU;rJl|KYJO(9@o1oD6@+8f$12)c;}ht1C+`j{0*>uwlnp6?M&F74i}v zl!W>u__~6fST@R_CQa`xnX&wzff_7fNYX%`kVfn&XUpCd7kk-g0p>WSczR@M!>rwONJAzmHgiU80g*<3qxO28#-d;nD(?4gc&s_%^ZYav<@^J{FjkvuL zdSc~OIZN4p2ws$RU3RGMpz$WRB6$W(^{lmjZy#)5)vues4Kf+Z4f3o!zRi0p9^U10 zHk^^nqY*yF-On-u&hVzP48JCVuh@^@9R70o3tJgJp2N-yHe|or31Ly;Q9I!JDjl+N zy*=08?#S5jXU|YcA@%RsEHtq2uL{8Okiv~XX>m{pCHziDt>E)1dHv9+0->}EOLsNv zA8<^$CeyIKid8i?(6Jbn7+hLWo=h9(rlW6Uf$0#8*#;i)bC7zMLlxqFkEl3>#Pm)h z&{Ed2OF6tKm84Oo9I|eBNMV-zN8^Hs^-@X>FXA8)c*7{c+w17HG$%rIOr|F_H&yrB zq@F71SZ?ur=PO!Lx5}BzIqVg6#6CI?`9pg2?I(D@BD-y?8$(OBgt78G?JGN zklVu_Fq=R!H!To9-_!vVSItR-l>fUeh<{i9JCiO#xIn}-EGUk?=T1N8eQHm&CH2T) zT+ei%-zZgW)_a5SC-|2Y${Bc<>lh;`?3*Npa@w>fte;>;O7++alTt1Bnco4AkJbP_ zR@m=at;9A__-A5(ptldaOvQn!xrU>=X9E%JsW$piNd5>L4dP64Bc=S~U=mw~k8O6# z+(j5^w!fYeRN|wypD_JJbI5enVphQp$ln zH}J*Wr20~lp?%1w#2GP)7QGZJzp1ys;S#5}{=lZfJ9dP1pmIKaSaH)P&hfDq7op5) z2Q+nwxK*7EP7wSdx=^%A(z*lm3Gys185uWV&^9vA#eGd!xen{m_>v(5hP$dQua+0M z=|E5$Y;yuZgljZU6;dHymAp-vtc?>q?x7PpK9E<=EB3r_VBOzD3a!vSk#G$GFH^KA zM5bqB(;H0odHN9Fo9YcE&({~5_}mflR5J2LXAr8en}ZpQF0tD3qbjND${sS%7QDM| zN%_DpY#!o`mN``@r{$y{ly*;L%JcoVIGg`xvx5P6{^#&#t>@Pgzc)nb1`(2ivj4Lx z{O>YqwUxHyKD&vy+e7+O0F;4GS9>;fEy2DZZi?i)rpgcIx1%&j2&I8N!oB`^QYuPA zmC=Fem3ZHm6JfJ$E#@(7p3mmHS&E^UgZ=(mtiPD9i;If2$Hk^-M$eJ%!FMkNLC~JN zwRh_y`4zS=k3`EpA&lwBT3vNM5}<**d^JaHnbw9+kx5c$Q$K=>-F5V1ZR{%n&D zCwnv(%J}_XzUr8Loii{<8A5^C^6xgjuuNB(q%G)QB&r@Kvs_7t&rD!($W(LZAw9JN zYOR>AGNzZ~R|$QrjDAnO=T;oeiHJ_yod)hnkl*>8_8?9V3&lTLU_UC2dbl5pP;yst z5s?H_8v+eR{?^%zMxhV7i@`Buox*k#i84#UERgC+eKmmAS6Guc87Jl8Fe>#~LKnI* za{9+$ELY>(M5os)nM8fdIRZ^^MS84*(g;*S?T;jw#J%{D?UQ$nSwD!9esqHK6%%OZ5V*g;t4!X+<9?~c&(HwQs^ z`oY7=3a%@^+3#~FqF8r-o^H>*pvP`MWE})ha?WdA_+&)tP$X6>TvTiSLP)o9M*uhe zmHx1m*BP8+h4kigUPd3WWWUa*9?B~(#ZU^yaGtyge^Zq5nl^gSl3M&cA;+few|zm{ z{Ti0$2sL}xy}BuEr^OlHtjDoP#gTF?SLIa)vuVin(_xn2D}~T)E<`kMEY$TyHIPaK z%+lD}e0GHp`g&w3#6VSf4#>qN)^|X{Nxu(1Tnh{Dq0OfE|E6&S7{teY5Pal$?>e?Q zusv7oz7V+PpS?FJ)4Et!;xjbJm~YBzK|3-3`POelY7FV(`^T^~bF6bCT?q5~w6p&M zzE;-GE&f3k=zIDDRX(an;$Lzm!QIoR=EZ3(!xhDVpfo#@BCij^x#{U$^!Uf4zO%56 zHyvDy^JB->IHYb|D#&ru6L;ylkw;6#{R}>{ANr(+Oi^fZ`YO>|z6dlH|L_Hx|HPbsS6J(fWPDIBDX1z$#j;Pc16;b!!yA++; zR#$(rST*=DPTE7p_uHmh8669kQC@d5m|C_ec>yy}eq}=d)?^^p9Y^HL z@j(tn4397@c$I(oE^kD+!)Nt)POFW)4P4$3cfCsohcQm9xm1iW%aZ8wG$K7cNBC)v zaa}FvzUT#)N73091n@N*@Wo>(_UT$Jy`>;fXOz?e1aEv!n_4wg#CtBPWC)(eYNPI* zLqYI2Rg8l93!#Z9n72vZwy#>}(!0||4R;Q;l4e{4De?xU7HT1h#c{<Vd z9BTpkJiIu#(N}C>rAIudfoR*vOs) zdmB1C2II3X%+kQ7j*t0COVWG;{tm@;%cG%zo$T}NTkgEUG&qy=wGAo>`CRP4Z76H` zHTk@gGquNQ{Aipl3WAOU1ymgnFMLbmG7&M7@TR#E_l2NfM;9wMY%|;&+S{)J4xCx? zj((Q7f}m8xCe2+G)DD;TQDljk!-h*n(+l{dO+2?m z6r_6e9s_)>Z@;CCgGCE?LT{TH30uA_ym!BWPtujb1HRte;4PZi-^>NupbYs+u@z30 zLY0c{W-Z*yhdixNFU+`X>DL@F8yK4hF8PO8j$MPEm>i{;}_rp+IqXJ`zq{;?IM>i@Z`gg;7T^eam zwTpZ$nK9K6i4i`xhRIV|>`N@J!9Kn4{;W}GU9XLjO!WkuL+K&!dc>#I`1kBFT(m^0 zY%w(63qdMOG5cIUOkgPbl!YipL(LtoneQ6Z84;c7`(_*0{oJ3ybjBAwT;|GxhNWU! z=_AU!O^keDX!_*V?yKS2Y(q+y^oHHTECZGOqc+Yb3~>=UUdvNubVQ{P1Rujo6Ps6U zn%dG)Yhqn-G0aEe`-|sxVZS7LWJcBrqVYxy&^s$~UBLtXl45GZ9WLJWn9i5m z51t{Y;TQSx_b$-ZwP@dPX13Uw9uHil5kC_4hcNtUVAr^I6Kr=Nvhu4uXT?Ocn!CoO z<44tvNl(`O(EzDh$43!=`GnG_SYIHIeLVe73v1UzcP+~w@&=un z$vz0u8j*czkd5a&VWyI$I{kE+&`y=Q)7hZb*RQTmY+UxC;^o5LL@CoqqZ~{Nb~`_< z=t;GWsBl-yee^ZqU@!8$Q-XCXZ_J%?Bs}pK!(r9~7QzV2q_5H6lGN6E!f?TUq+Wst zo`J>H?i+R@`}D_Ft<&VantKpOobSVGNX~qCXz*sH)1o>-VzMEDlp56dqAjeMk$5Xz zbg5~MT11WywwqtesHe-+DBTeEivWH8*l(cljPPO_LeHJ>F(m6C>QHc2UCedSq_B_d zHTK}G{SW+EyMKKX8_Yy7fUf+emJSC;Xx;&&qq$N;fiD4|ecEnxIWs zYo9E~_XiVy2N}_2yPi4~qlB0ZU<@`+Do|}U594ZvKj`CIx6lX>l#;A%KxtsjT~r>; z;_{mYBcgEyo0|MVv(K75oq`Psm3_BdnC!f&jUWaUMVa@XeyAZy4#V=KI_Ysg!^<|a zWB{H0mMaXEWuUZ?Ny=3F3JndJS2Anw5|te#GUVKr>%aEHE%W3A332w+rjhqmfEuOM zILzTzifePK>yp=J`T{-M{8K&}xIFLj+~MD!_Z|w<-#^hUIo?M|gcX$?cT6)r78F5d zew`KWh5?x>{=Xtpky+EGVK9dSb>(eOx|ihXj7fbVG`>G6@EqSF!hRaU1Ey0cOr<>6 z6-3_~fpkYRWWpo+j|m%Hj-Anu3E3~u?o^KHVd70t2Q2H2drFvyp5{Gaqg3ZcBY&M( zvpkQyn!i^SYl2>le_f*ZT|}mn-b8O_D)TBdSsf7vlMk@#YdXcsVOViD zWrUW!kmt4DC@l;YI~KpS{<0p@+9ant#4oxZi&Y~0>+fNg9?6IH@NO!qDCOu88UxPg z`*AZ)@d(jAQ!*37zvBcfrc8r$9kmdx67^^uaq#oW>YR4UVJht2SGP4!KJCZVUrCl! zBYBYziQRdW#0M&YJ!8@9bMRt1`0pUCWG`C}O5sDoXw^1r*9Kjs4?Yz5@P>4Frc3q| z<-WY5xMHQ8lBo!vUQ(_uB`tQdo3Bv0m!l^t(I6_~SQjce^YVy(tzL$0QY+`MilzrC zRiuJzcXb?;U{2ERc1`$rofKYG(0UzFbQ-Ul>ID9UK>LfoRXyIH47=;IwuzYgIFz%4 z6eQRb94ZB}z(V$^EjS^1kMkp#<|sgWpk>f5A;?$y#6v4A+^-}*7bs#~_+edt`v`Gf zUUJa~>KJIFa!90}&7q-LJXM$|j-41~DeIEo`Z`{aSc-)Sm1NxYv)Ek5Jhn}_3f{8j z-7wy^Z{87^PB%F?|BbooGydRwk|mRJ9^#O?>e6nuleng@V(i{$w|66Rs?*Tu{yj}s zp04_BpWeJ=vBRB-HPwfy%(Dtc83cImHz^C~7wNZ!r#@y~P3PPoH1$nMG)&J1M}jf^ zF+C}mQ%090ShU~teeG0$F!pGbHDg=_Y)JI7i&31l;#@EqC)!c!`{*tK7dc74WPjl~ zsPe#2x4p`ZC9|5&IPW?5IXEH^6ac}PakfbTrRCfipTpS$Q^Ve6VP^fYS&fyQ97KeWJ#?105o^{6&pdzVI@-jWTu;V8E+ z=W(;D0}&q2oV^dh`Ds%pf=CJOQApG4PK zMK6zXH0t*zrX#Da*ncSwXR&Ul=dm4+7EA*E}c>kJ38dh>Mp>nkbN<=L~p zLsYlFExe^8UC!TP{Wbkz^2ks}gfO8@*rSQwYK|XtR`K<1*)MZyCfB@GeowsnIpvJ7Jb%!P4^4g9WGbe@N)`>3Uwk>hnq-0T9OSgpa-av^ob{ zrLA)lS}+oWntpdk>^MOk-0j7k+|14*O#UH#dkzyWG^ZnIXip_jpgSwSrbaPYG*l6L zkFREhnyTUEx~~^ReRv*Na3L=5!k7_hKriXvxP%b;m$Vr9ItGYZdER7ir~gUXAx{+B z3_Uc?_*RM%Q+#ZmoBMEl;HcH^=f3U#;N(W8A67ce_Xw!P_~B;k0{QFX~v|jmyDi0<^!?g1)RErw=S639RloBMW9wB1J+Zjf7)5QK3u9qp7^h_j%uvS*dkqxTKHtklCdAT z#75-soD7oC{RLjB<2o4n!r9YUx2%EudY9;^t`opb30ku+CJuP*nYaSD8HW=O`fo&8 zyC=K+4FM}tM*onMvNa%jx-je7;i6ix3z_N?#ZI=L7rg4$8!2Patb~#LpxPFx4qmGg zRe9^p;($t%gyDdP%OA^l(W>sH8u~EqBd2!PuIjMOT^VkJ$k95&=T0}F>Ne3Z^_+cu zy?Rs2DyB^#B0jImt_AKKo1CN{T*&1GwsEAFN+W+V7YhmS@zWGjw zrGEY~;L@?3qnOe~kp8U8BP6WP>kL*$A~JBoV3dM=lHX=b=Z0ye2EXlgeA)w41ZSet zg&WlF*UB+_#2_=$M<8Xb;_S=w=n}1d@)@!}<>b|3WDCg(67G|V0QpfdFJ_BlyYs1} z`tb?O9*$)xE)YxQl3ekNhA#XV?sL(tjEJ);tDSk zhAsX3#(BT~V@g+wCqhujt%yUXwea&A3PP~pa1B3%h)`3J*$z+ZnVDA(iS(zYA``Md zJbY9TD&(i}+Qh=Uhf3I4xwj=!QJ$V;oWH}rfrK}1D{El7=+Y)w%GLNnZ`wBBXP%c0 zI|m#5RGC~$-R5u{;F8}Ol9ZGzsl0idj^nRCv~zkp>Py+ox$)tlh=)$Wm28L{i_j^u zRsEIyLtx>@tvTYes!!isY)P&pl{Z4Wh(x$IQ%p_Y;niFdDJf(vvMy@FE2Fe$M0pqA z_Zn((zqybQXHmaXw@WD2XKpi|j@z$N28#XWjo%Rh%i?MZZ`rKJnBnDCf`-I#=~ZcC$}d!`0Ti zYUkM0NJZ6h^Qro!IyC=Yugb1+u$-VFIqc1AyS{J7@fGS5`rZXTydl=cSqI=YZVV<= zrYF|L)a-~^vF2~v+~%}Tl`{yD9!2I78O3Of&kDzpitgqU3gVknWM$Sz=#a;YA5Gj`Xn#eh2ra4LPV&c3d!Wcc9>QFq%X#y;kt|CI8y-Uh_uSzke0vcQ@hK^>a_)TJoUS zZ1>a6;03ZZ=hLP0a9)~r-W$^tD%!$ z9j)o3%{+r^R&4Gnu2jEV=nS$DL|XK>gND~hg+@5j!B$3o+5y5QE7y6g_YYA}lSB@n zqbXBB*-ox@iJ&es-(fjLL-e14ak;P^q?JOkz*iPl?u#LX`FE5wcOv!#`BC?c;KSW1iNTGC*Yo7yvGIy`&{EzDV~!&3Hy{XMFfFp&X)I0b=IyS4#X~q525v( zMty<-h+G4;7yf4)?RspD8y$iTekbp27Kyq!+g^B7^Ph3Cc2Q@D{b?Dxw_+X=h?%|M ztJDdZN~GRBF?ucG1>>8JZpl4&DbvPzNb58^L>X}1T!=Zp;2jqDqD}Xe7?pcAO4$93xk*Z zXEZOz;sNNbzjyadQ{=RUxPk|%W)<=oLkm$(aEGfFeK_d9fryqgb?O2>cyHkX=rY2) z8wb}wMD6zWL{%1+QiTgulO{SYI!vNdz|ZLnw}@^;OU(atIsSJYzeS(1EO?+t|I0FK z%Jib(H>7T$x@!TLi7)f2Afp=r&wX8xoED0~R7BW-q+y4!ONzp^5L^*uVZLy_f)JL2 z-B)z0Z)&$~ex#YB!5g9GB_#JfC{wewIiA(NJV_&WjUSVj^<7qQj{Gn-vLrdA6P1sz zSA$0MdtK{m*pT+n43puSViq%`qIk=4#HY|Y zmmsKsv>5Jin>{}?QA;`CUjD+AD4?9ZB_HtHK?1_iBBjK_PHX}#a( z27&e`%jA%}Ahm;B_!nA&rt20=(YD;V*OSW`?P(C{|VWwAkynQBwlg+`rk>-}|d+zwxqt zMP2AdS8cv$;on>;UjGWJPjSEVZ|YiCG47el9{si%Rz9_>qq=m&jfK4(v;vnO@0(iH zrK3H?ZC>++73r5Je2G7`Rb$cNoh>Fuzf|?STp<7G&+3JXx>?T^Zh73toVHjhr*-#r zfA@#3P0wtXP2Kz~`E1rvp<_D&{TG|4CgeSI6$u_x!GtY(fcN7BFkJ*TS%DYJ2QXa< z`nCjAq)p$-ATkA%9hg8zg?mLYXlnYZGU$o~WH4$1&t3%PLXa|G28Hl|*Xw9zLJkvW z1xYbYo7BYs+ED|%_Z7kcF+fEnFy8_hP&H5m(N2Oa1jK< z8)RD0MPN8+W-MS?x)^GUNTBB|hA2&Aw+zONC1-($sV|yrlGY&B<#Ul%!ptDof+O0~ z6&PW_IK4O!j7x#uh=4-`6D%kx5J6AGX}|=<)N|1lxHAh417+apYOx9A%rG`!Ck&i2 oL8;Ric;^%F2ryJU3tC}-D-NIvNMM5KS&$UY1hSAynE(Gx0P;{wfdBvi diff --git a/docs/development/assets/hardware/j-link-edu.jpg b/docs/development/assets/hardware/j-link-edu.jpg deleted file mode 100644 index 888209f50c4f36436bb11f32a2c93be8762a8a8c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 16001 zcmbWe2{@GP|2I6X+GR_Ksf2{2EG1^{awDV(p@_LlWtlX$?2MT^vTsEQG08H?GTC>N zJ*3GVVi+OIm>JB>#ca>j?|=NC=l49%?>&z9eJ{s(&34W;=l43l+voHB5`Gs>Lk^pp zn3+JfZG%9zfqxL80CL&L+W5*Xgth*0*9RINe?N3R?x%J3-0{=C-tJFakDHmB9yh;f zY*^8e{1`~(r( zv+dZnojbOjglrevwnJ>2upI&gh1~V8<$;p^*RgH;j-9)9i-6164^F5$3@(4i4sg-C zz!ihDL%`1=JH>X1pU}FpTf*v|$Vo5B^Uq%9>`}a0)*@xy&p37A{?pLC`;JH-m626a zRynPDMq5W$@8TtWqd$#JOs|=l+uX9Xv%h`E!R5ijN3L$}9^O8_e*OW0L1E9sBO;@s zW0I0zrKG04PS1Fko0nfecwhLTyrQzIx~8_SzO}8rqqFOCchA7!(D2CU_p$LA>g>;@3@KbH4l7A`&Bf6Rb?pyQMS;_>E0L{2$UzgtkK~&}B=+q= zA>>hslq@mlte5HFE&DFn8d@*2!p5oomaK02Ga*F1IKy5D`5cEz84^O=6B8Z2;1`jS z=o}&Be(wYL);_!bR@>n3X?CZ%orM&XzR7Em307<{dW)`45QHP~`owm)!t!mw1e0Cn zOA-WmSd#?gJ2(1#g%GH<2yV+wZv=0R3Y4H>62DoHVkr9`+v`!pd`=7M8;!t~6=E(i zs5rjvl2qKZQ50b?;HGO^u~(S@%NM# z|6TKe0BIlWaV9@4J2%tO4A!s7XDV1?OlL*okdlJq4aC^S;6i6bA*7d>S+2?5Xt1jT z8eg1Kdw1~&E14VRi!Ng!V&KznnvXg5rPN?D(*C`J5w!;g^;v>5%@HE(~Vm=-aC2KOs{YyHSL@8SiT_LU;c{(hB4{b z+jI)SzT-}5dgDuG5u@ObNMmv{$dv}F+scOKL`~Ot%8K*#3b$s7P3_)9ea-WG()}!< zbm>*z@CKoUK2Dk;c7{CdZL8NvB|JP^nBO!XtDC>?ltZYgp#13AT>%@u=`PB+)oO_e zf;SensH`^R4*4JOd3Uj(^MbWRLg5^wiI6K{CwFp zVi}u)03^JSZ!Ebcyg&Fk^n9jtVxxt+z$bHhP&}lXy~zJOtHbf9RXnM|l}9Gh9zt<# z6|O>vJh4YKBB)&;&D@z``$Gshofc&OXs-s+DJr885g_pod<6UIq2H`x{`nEATBaNQ z1kFbBrdFfC_ZPwC_2GB|!TC(UEXOd||J_AFQ?NgwL;5bhu;cjlfX^F**AXx#;q}*Z zcd@sqCZalb-^xW2mhTc1U@|`f@a^N82^*qE%yLmdnpp>=t;Uqv?T;j_tZU52SJN$f z<%k@G`u9{mhrV<@zRA?wTZ*Q;lo)YfWkcc?AiE z4Pp++6lnlvPUC4Zie_rUbYxhhJ%Gsd!PSM7so)|tZBtFfRdgo*!>_9aiG zXs(Ka+f1~TdieLr?^Bel%a7%w`KY!H(FuHuvldWR!jonY+K6IiC2q3$U$X)au8gqh z?ApPn@4A}u#`G9pddq8@E(rE%Q4taW_HA2{5!n6iF1MNa!}FOl8nVcv`5o;+Rn=@y zxb?I9W*Sh=Qw!dO5c}wy?sd6BRhW5}A9ZT-A z!?QG;^!RJxqxVyOKxbDV)1wqF_3n9d8illr$^fDj5lEm+d zX!z){@w2fzWwSIv2$?}fYgCo&!iCJkQx={4y4bwsR)Hky0)T86eK#2&eT<|OoR!(( z`y>gv>4vJhT=e>unZ*^RarY^H0KvEheR0`b(fYhGjKasw3Z#nfZ@oBW6&EK;(9sqN zmtp1huKy!Lo<&5(Nn~#ruI@1SsMHyJYi`f6T3(^(R<1ECkr7c2KBQ$S$oc-)(vjB4fZPyn2o7&V^Os(BD&{*8{Y%{5-|m{KSodbzqX z$X(Oq?W@{A90SzakJMxoJe&1ADHycWq@8p`pFymifqnt+__t@bP~SE1X71doI>W@o0t zipj)Z3fsS}RP7Z)MwgC^8{GVHO$eb~E2<}{;U2&zpr1%PHG~ik(zu`61hHmW|CLw3 z6>2Ol-QV8}J2F8Ehm+RrCn?+Dk3}Oi7=#&kIL4h>+Sb`@z|2nf+^-pa!lLfU6JE)v zp17$9FStXLSLru)_Z6zuvrs3*Zzbzxlfzlv>T#^SA)`Sovjezt-m;&3Ac|FcsYEK12G5@2;&*QL4&-ljMk#zQiiQcAkATK$_lDwJ3g(PFqKR zn9$@^qz4HhpAZf}sdrn5u^+xd2- z+*R}QLtKxTm`mdGI!Twp)G$4tgGwx%y@vjiNqNJM`p{|U=h!m?_bvN;XBvLl8u~ld zQ%UkXtq&c#=`v7E%Q(qhQ$vwdk=lc-(?1XA?L{$9QmIaI?Rr7DAGd1L6%+YYo+VBJ zCbPkNi&A+`N2_Wh+mGO}P?BISh~7#UpFruK$8tsI>|e!3(WjGCv9lW`h_I>SnQdEN zGSmk#FZpDSTJ!n2m*JMh!Os$|yP($zCVwh^6SsL%*~STdt%y6KfZzMZUK&W0Tt%;%=Y3LzRSRUxDf zy`9Hm(A#i_c%ERY=8L5?D+3aYi2d|v*a;wUy2#z9A8o?c7mGQ}< z)GFsYMH*-07p>=S&>b&q5WDbVjXM~*Z506(RCIhLUUczA2;bCU$ZitOT;h#`m(JHA z#KS!`BV{>ZjTX66?odgAJXG|T{!m7eQd6V7zv#}IU{c*r#M8*q{mjpe7cu!cF_?+_S4Z=Hqw=Sy5~KN|l^`nGO_*@(Xcp@(8vY z5Hdp##aB$Fp-V6~n5VqlNTLSkA5FfB_p73j$!m^nvUFDuCOT3GsaD}hKACOXs#%#~ z%CXHyB&hr^M08HT2-)%)=F+YP9%)?Sb7{X|L68o*emQmkKN9{3H-^4dKiYga;K(&r z@G`mrQ3{%9O-+I3=FjpQ3-@s!tCj=Px@Wh7MjBI;2j{CQ%PY96Q40wlMqTF;d6)OI zQy8MOI+ZpdK>yj8UsB5y9ktcbAECWeIJgV5<>9N>3(N$gAQ9a76g0RxaZx2 z-oabZ@&NZ!y(ca7c0k2d#zM4Q&nRt_erlrT{1bsj3TrbuxU7KjpcD61?eq+z-*cQJ zs8k)ztU(yfq42;d&ZlmYJ05V-@<{5Mk&bCu#U3>-Ah0o<5v#x>1D`2f;zaUK8ka?* z>?b|a99x*iNBfG(Vw3^-8TuiQ`ns|AOR_gIUi6*BdCzg91vGyaG&K{;@feq!&aAY{ zGxts@Z9kyZoww=7UbGP`Q&9|?JqXwREH zw!=qof$(Wtj&vLS*e{A0M(N?KT}pDbdwxTT#s8dM|Ho5$js@#al^tUDCTsj z%OC$60tFE%u`_Xebfz<(5y_5Z`iE-X`~G4%*=do-=LS-~#FOZ$#IYbCSFn%6h2hWv zde`|mK5{nfCb>shr8@A!OnbnC6}w*-+`d>@VvF+do)^(7niexjEEHwQ#KU zy=_W{2q9f+XTBPtynceyZ=f7be<}I-Y%K&;cll`FogW-}q{690hi}O{aH~yfMc)OK ztN{BKv^ehJl8A9CnuYV`_i(OV@P%d|x-(Y78m}uPv>G4n!Z8UQ(47lQUgm*!@#blY zBgF@Drb&C-sH4o!-_&u{c^@q#iUL*Hi4{ewYc)7;Uks9aDZq#t*^UF$(>jo`*&6+< z%buDo8JB<6hxC29k-BDl@@jSeRm$q-T2)BzvAYnF!Hi&qJt{R)z4~|85~?fe{>}{b zTPi*~SR*5E=sso6MvUZLr@vXAS$bIDGb>B}%y&1aoZvLrCd&nhe$CtW zGb+;A8=7^vGXCl!NeIMgp@Kb-W7TXckGt5mg-Ei38EGZ zx+6M;Ci%Lr2P@!LPZQ7cGhkqb**eI$STjrzLZZLEvZmOOnL>yk5|9e=40sy*yv}*S z+TVWP>34be{vBuEZZ>4tMKh&aGKl~1tlX3bS(&PyXJ=WaP6gHP--@-OfM zRKZqu;UM&{HEuo+C->kX&-}ET+{uv^KaMXSw zBeRbuI`qGgi}OYr&a1k7DQF-)n>wA0XcV-k;{K&tOJNn~Gs_@h25X}t~~kJ zEuC@s7Hi;-e7Ra^mcIBoQvBhKqbzM6lN%Z|r1!VfKP?yY<3M<@^zLFUM3evwF+V@O z0xfaX`%6@PK|&xU)A{3#&pR{227%A#xlbbS8)q&d|4`9#OsM0#;d4Wb56A6Nn8!ze z9`2r{+Hu8m#6R#QmIJSFAKIs0{fKW0wu_#;y>snR7m^qBN@~T}!uZ_rwb|ck+|Qt) zbcJ^@l@mYqk(NOiV1Dz8qQa}XWO-bQS@s6u`$2R#@p@lN>Y z1ilF*l}0BVoQqsa7GI$BZO1J=y=5&9^l!XG1Ocav6Mt|PN17JcIzY)WM}g>aP2gHv zUru9|U&!JKFj?W#I~!M=cF%sTe}Xd0&)Kk)v~u>UwKA53{M*>p#d{3c=7J}u65hGd zgcHNX&SEM^Wn|MaJmW|UPmQ_WAvii>aJdi(csrD@`5GSDLIr<^PsFo(k=4GN>q5vb z6W~bpZXkz%L4Tv^eh`l>2i6e%29fur(a7 zcQe^|XnOd*K=ftD&6-#){3iYeh*JpMc)P~;p@A?#$}bhSAFbBkw$xhm+k-~pDnRA< zu~G8w#v!fE(L~-M=7X0O{8)coCl~_Q6@2nZlIBHhRk4zagw}z7Q3iRD3jPabbIdma zI;_g@<^iqj75EviiMZ*T*N#uK2@e9BK=#Gl{p>#qj)(ri`buv-6Brv9pM@US{V)cyP=kWf1R9M1mXo@~uO@>ah$*bP+mE;B;ubH-A>3B$(?=hLl|-x*V)3O;+zm5AsNx5Bk5(IN=hS6a{;YxlrsN4pK!q zin-0t`zz6`j;Zrp_Z#r^a(jj+vze}oQ1fxGS=D&T^#Fa(-*cSc37g!c#E|?{0Cac=*;cz$ONE8S9f=Un}+?Xi!~~ zWx3y`dejHia**~WTBEpM2nq4%>}2znYT;*3s1Rod!rj%hMaGePU`p;nh!ju6ow{r+ z)~nJT2&RArD#*r^kMOp_Au*Je1Ev;|X>sFjJdXIZLh1_)22#Iyp33BeqPn|sU zzS~@Xm!#G0SO1=POD!NPIW0wqMCi^cQsns#>2X5Mx=+n3Tv0tDZZJ_8Dc zN?3bG{=rv!YjoiLlWpYL8>jQ2Z~7&>O0Q4}h4b6hr;}-BM-Lwu*n8_x$`_0~&@@dR z^sxm`cXrqjacG%-Z1?RBi zQ#wPw6DUH&a*G(QLs~Kui=1rPuGG8`p36yc>9G z?@9uM5D-DMqMwgY9s{{d)2oan==3lvD#sl@X%|Aidly;73CEbJq%n{)qU{KI5pG(& zX1K#Z4}u#!1S5;`*PS%m$YY7qqOC>58s0@fafYV9slViM-3*-vx|`Am6p-lLB(t zL(DYZKQIYkM~f~UL?}Fas$;yvDxA%WJ(>jPC0YEEV9H56hihkivskHn?lI9>u!{>3>;SoK@BOKX4}6BAPDwt zV~WpnxN6sju}1@*&IsnSTnndw3L7xs%ieW%7DBl0&K-wj`^sc%Cx-LUx9afI-WD>E zG5r)UBeNO3$B!hrI>sjfqpjnl_)-ahb7L?ybMg-OVYPS9H<10V`hxw26w%fk`zkNT zF5zdxj^1884;SCLfYoqW1GRc1Q02xdn|;crpyNs5;F>K99Yj+Z1KLtR*xEIEwd)d z02$(0aJPWAUU{v$I`$-gEZ^xB^U@*dgI8~qD(^D`ZG1O=TObs)N41<6S*cIlf<*->v+bUQai-6G8~?r`BD5Kj0R#g1u?4{6rvZgMr&G zfO<2C>3Fy9u#&qBVhjr(2~!8jJuu0G%3|=%k#HtcnyH9ux;>gpQ?0D|b?elu;_A4X zS}XSS0LF8s7cTkhJiU@sbLZ^~16&QOT`MKMB z_!GJ_z`_T8J!9;0(F>U!O=8C9W}D2d$|lzH&xQ40+8W&U(qvC30$%bkfc^<91Ef!f zIL<62RMrxGLi{ZN(LHsG73TJO&THwtpli>u)lbl!VBncPJS%r5(A*PxQS!>kyC8S^H-g`_i_2 zz`G46UWuy!5-w#U)%dak(R5xDDWqr|_k<{N2Ll`0z>lwL=+QFl!tUulV>+6}$O|Fk z*%A#Q6+OK?Pj|JD9NhQyGxGbVs|i%fcvzd-Ti_}R5rN-ra3p@ZuvBF0NLk^J4sM+t zV)ojsK!1xDrju(bvf?qd5tvUm8*5AIe{O^6&wNiM?p5i@8-G0A@h!QKER~m4?Z~R1 z@booEqo##xTS`-pG%z$jIjb|Bt8#%0S0isRuV)(qRsJqB^aEEZdMS#3WczmYuCKVO zrIUu6#dtD+Q7O+Sj9Td@3rqHPJya;&B7}s)$413UCTO8ERT}pWkkJkFyBa~nR>Tp( z7bpY<1&E*UmFN!mAz-45a=0osQwWg*f?HpZq8`--HrrOMX}o(`t&UtDMzvwo7@TQh zDB8e+sWO9JsVD_{L`4DfwF&!J>e<}9ML+hI!79^i-d*3gvBn;!Ev`a$p>T$SXr5 z;d{{9P!T}SDN`U`z^JB(7|n*j{`9S`{n!AyFt{t4^7;%5C9{# zJ)^2L+_m(3BhmxVV6f#cX{?S0m85(v!PcBd$2XELaNNt3D0gBR((D$1PeAF%;dWM$ z#ZU^+mnXRP?R;}8mwT1!W|ii#WZmaF=ZKJGTF#vb>{fr0D37UDxzOpNzHIwyvV0h*!=VbEPfYG)Es?=(%KXaD-kzt9C!pIc$2_btT@cAgcX4T}m>?e~8@SaB83_mEd`BE-vZnFTwTL zIz2T^w=GYe!TE#})pqkiZUv-?f zBVkk4(Oe{wN16fwi!V`A&M3*b|8ZX-Irs9`>36jU!CLm)?f*R*MFsl~GHkJGyj`^; z+P#)rHQ~KWx(djtfKb7fW+yyTFc!nbS83ze|!`py*o`?_a?@eIhEs22*CB$WPYx3GIVmu(7f<@Z8Fsp?=|=^ zgjh})5>!TrOxY z?i{0s43fysO>?GWB6A=Z%v*cKg7>6-Bq(IW_gpW`U(|mRNhnBpw>UE57rkbRdMMs; z0LPHpMD4Hw`WcCqObql;sX*BcqyS$a&bEI`wl)I^qv@Mx=MjLEd%&vUBcuqW<86S+ zs8emm*dSMY!J2#0SrJpNl3rGgsiNX{2_ddB8&2>R=tQ&HfHwLVAYntghP=@jv%0n3 zHrViCk+aeuJJXn`=tH4YQvNLQ%~4*VR42CL4+Ac388t2Lxy;9cGfaIq2d9sjE2?O} zeoOe4(T&U;#F@RiJW{h@-!JSz!8b54)O=Wm9cYNqxX`|}yKAIUQ{O&d=H;YIZ9F07 zNI>3N-X?ogdYbaxo(%&Y7PvJ_4H;;<_!eHtHxNgn9Fp^=$_}8xGO((~J;?aKuUC<-V{f{ZTSrep<5}4*?(?IxKK8b0}N@&_@G=DXB zUrpE2V)?+?HPFTQbm|5CQ3=!Mr^eM-s9Gq_J!&I}SS zTkO>le5h#ert2mYG{_m^*ukra%pO4dM0YCANi1A2m(*r+v1jBDOa*gC zC$t9Nz6n!uYZhZTu~J4}y1Z>e%|!J$;PUB#kLm|lnlGQwCVDn=9)VB|tTEyyM_oL* zasgfDHOZe8B+3}s>A80>e?+!BOEarwSTxvVsrageX6lKinn1R|8zCq_)*;QI+AQ*- z=__0#{0w<)a{O`>o#!*yKs1I2Jc!aK8WK1m~-GvqkJ#j&+Xv^gT+?e#B%l% z&O9ttRZB*5bZB34j}6Zxfl|vNC|nd-bgc5;E~Y=5##fE~W;34_X9V2G%ja>d1Feh| zN&E|uA%B1@Q~%3l2P7jpAVG6#(*4meoD_WCQ3(00AzAas7M*7yEXjFtxc|1!RI;p5Uy?!xaeLBGr2i5*HuLjPb@0Z>~NMFFmRaxZ~9);$IWVotmFwNli=La zLEF8xmS!SGYa+H`D>a4hjRhYTKxs!G68_$;MgRzmhC6`QY`pi3ZZmFRqc_b0UZsq5U5M3fhAt<$DV#7`n7eD=FS|QOUhpQ_bNv$W zwNlJg@!QR7xT20=`xfNUuJ`WU$J*vgGeV+0y7H{7-dG;F5R>M@#rhWci^;_9c)z%4 z{Uma9bI`13VLU&l;hETR;whg(w^KgKNvD5i+IhB(Uc( zrK%h^_+>)vB~zt~65cGwA7ytprocnTBbB85M4Y|m*O&RKB-i>^n=GorX?}TL1X8Va z3K|1lHNaoC&jtwWXds1Zk*Mr+|CYUAkHEZRI1aLvW;?>u%Qc-}hMg*lorZKmZUCD#oToS7i+RH~0bM^t6j-rDWqZ{PWg^%8wnMsT zIOd>7Hqo0q3f7H^l16clk#Rvoh=ar^rSe#ADiZXn-~2|CdQL_Ocz(30bng%}RKcIR z%Tzm0yLiTZT3bV=TZKo5wK0sx3539t7h2D;73!P0nvzV0I#d z8-+J6*gJ}-#a8@4r)X|^Y&i<{UU8qt4z+rLZL1g^KOy9U5{81j1s2Fp6z?L__Lq9d zfDr_}mn1Os+6U6_F&~CrYeqwJeXPK27bJ53`1b(?5qZlEnCSKl)2?{gq15N4Sw$eL zQQPHno;%IMM-k&$v2H6mi1V5(dqNP7#IxNRX6k*Cg}2keJXw?lJgXXhoGk-|dL>Tc zfc+RsIQC9JLrVrZ63s$xLw(!SPmRYg>Txx4LdeQ6C9E)Dt>O|L8zCaTwV+eM=xskA zfOER`oT3=hR-XK|hX0vmx%>C7zbU&K z@3?+g?3Q8^JReFk!A8~gglfzkCJ3p+^tzh9h>KBG}>%4-`b}UmP$qxgYi= zS=%GD?T#u3_}^citM7{8 zA*h$r8isvkl>LQ}JM##uGyMs<9$f=4b$$W%DB#F((910B!83LewV9DL_gUJ5rqbA* z4iAu@QW?KRp4)z+E7ObKao#@RcmQ8b#m;G;c?aLS1FOhX>KbPm-k*2HZMvRfWh(x# z(9BX7Lh`)@7l8_}7pNnX0xWlKnIwzBan?ik!G;8*AO<`N&#=Rd$+hIuDn%tI0U0!S zSX&0F2hU+vYq(sxn$ei`(&N$(U_laocVfs;&1@Rd`3#sCMrYut#_Yss~RB z4jOd?r3nUO(Vz760`UOrp1SSP%}jMA zGqvt9XsNR{Gx0fAVUb({%y#HMiFL!TQLGvqeL%a*LM^~!;0#+KWDN1ix~Vjbio#1c zsqo6a6;C|?y?uPt@>(ybso~MHy&6Vcmx;CE z#F{1R028!?1CVA~?uH)t;xBbF11-@c z{OS{=;7p^lV7=Af`EZO~(}*%tnw`rh&|vo8n>)%3nn-Jdac7#wddR1 z5N6vEyt}u?&v9JT!8f0`TG7VnsSBIlr_>wZJ|q?9s6m+&p~3af6F0IyXWBDuQ}|?d zI4gXW06Lg8ZZS9&zrbJek8HFmc0yI#rADaTcD}W#p7STDHXq>9OA5yowI%&CvRqXlj>1H1GBWTp; zTxt{97(N)hki~aNf`6(u`fbRH>%`q)+s%_-YYu`wS@lqH%yMQrX-#dk+M`*Afr$Lc zRj#2fA5{h`ur@)7di*V?0o-iW^1YH3DYBlJzioyBf-AC4{0N^;^s}~P!aKGKxn%%$ z`~+C5!TSq(k&^f$9vKAK5ytMa_aJJq_YL0X&IT*a!(YeXYw{tW$?beNfVpm92=cIE z0KxoYWh!cUe}HulbAHoS`O&1}Nmn|~FU}|?Z}@YZgFo!&yBM|S-~K%^|0_CE(SRzn zRbqy$u!xu4xLxhAEEbYzrv(P} zLF!t40hyr(T0hgl8ej1~Pr0-hYlRTRe(2lFZAPyyA=HjNfu@+1EXqct6;Xa|4V`Zb zzW02jZ1{0jJMm!6Zz9 zc$hg9s~PJnk+_K(Ct}pnx?To!OV5mCqP#zV#F(>W1iNQo21aK4uj4(x{u117>?3jp z0a(zQ$9>dAS7+7!(X|@EF+ax@2X4xVbXuL9$t|L-Es35OJ9m=Mx_&;8( zo~h1RuLjLRb|GbQ)jdQ){@(ilYfHEdOtoTY742F!mSfmNJ?S{PS-9R;CtrZj{IV(S zN_K#WH!?eF+9*Gc$RIKA22-r7#WPN`ZJ z%{yKnKID8UX@AWSEk{9S4YV|iSeKgd#tuGtb>ioD3Y?BLFCK--D;%@1?SB$MWH0y+ z9b5{*uVlh*H^yhyJlW)I;u-r`=tvxBj$TG0VcG%Ii7&P4LW2D@rFhnEy!%#M-> za@Ne?+dwcp&!9F2C~dM%M6Ek*_!6Y0{vO2YJs59fdDs5n0nc;`X`9z;#4vn0J*-iJ z!9g$%RTVDR_vJr#JW(}N6>Ux7QkIT?Cvir$Hk#zxuu#S@={xVj+wY6+{9ZL}FxXzX z;vi;XM%&1XF$g*YKeHTu+C)|3<(D~CkJi%(tCz7UTVR^Cvy`zp2zOQMdvI>D5J+9@ z#Z}1W{kB&kd08Ix&9_OBCjCCWnY~5nehw3k9Zf&|1iNgB!_ct{Gj@dxG&_W`@Jt6d zqG2v)pJ{!&-qfIU04xZ9^7rJa893gJKL0k+;W+!rS`EbJk z68dyiGaU|Z07mC^NrZ0n;l`xBRyk=GOf@Nq+-~PoS?oYcgG{ffx5%9sv*#{SH{17c z!IZ#l$ttj{^Mqnd-$+&b{x(0NKh^1e7a|jsB~1p(KM?jJD0dA!!E{=bWPqy@q*H6ZM^B`?U4+xB=iF?A?rAMwh{UM zw;A+KnuyWbKw(de`WCRFqq?(sLAI)t_qCZZ@Vd<)M4Z30qU$SKMK@Y&FD-O2CT zhLnVzop3yc85x&K%b;-BcX7XT@Kw1|em!xgFrh)V#Df8-cC1E|fXt|gp!=$Uww9{z zoB0LgnQ7RUzz)G)3ioV)n6*1k>}-QRt~bPwSpe4kQPpssUsLQ=#(daJu+kv!a?Y4L zdkJ<;oo086mlo4`yO!`E_Es?mt_y>LOM!trK2B~W6$$CcnIQ41M~UK^yokDFa1)3q z29zi6Jf-Z22OAe2;ph`?cERwqQw^jIS*|X4rI_*{H{>aVHgJJ^26G4yRhekqJN>IO zXYRSDKoZ17I^oJ<#AyyzQ`S zfM@Q!HGxmMoVfXf#2FQt%Rp zUEfXpg%Ei8mH8hy%BHu9z|iq#k8<3N6SI9mNf+m&eytfdd|z02@ue3AGRckk--F~y zS$DXq8*sc3;{4*R)z7j|tfD!)^5dnSgK4})r5lJ8fz%`bWd{Hg%ws1Q$X32HTN+gT z9M?I}=5Y_kt5&dkz@)^9_i!}Sau#>QZEGj8Yo~GP90(5lhyueqb^T!tZp~&;O@0QJ zvanI`E|-)dbAT);-Sd@0{D%ImL|TGv0e|O@##Lz`+pW9$&#G_@ken|#J%OQf-*jRq zelJ$;r0Fy=QWlo}(MzK`I~2*?h(i&erH4QdCF7ADNYSLa0d?C({a5UJ-(UufGqjjN|O z*FWJHmgup}mZkD#Sq)B9DfoXw%l0J|0)AH+YK(V+vHq!fN4dU#sDWa^;yL{0LxRI8 zMNq*?deky(3N /dev/null && \ - $(GDB) $< -ex "target remote $(GDB_OPENOCD_REMOTE)" $(GDB_OPENOCD_INIT_CMDS)) || \ - $(GDB) $< -ex "target remote | $(OPENOCD_CMDLINE) -c \"gdb_port pipe;\"" $(GDB_OPENOCD_INIT_CMDS) + $(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS) diff --git a/make/openocd.mk b/make/openocd.mk index ec97939e856..3a8317ea95a 100644 --- a/make/openocd.mk +++ b/make/openocd.mk @@ -1,27 +1,49 @@ -.PHONY: openocd - -OPENOCD_CMD ?= openocd -OPENOCD_INTERFACE ?= stlink-v2 - -ifeq ($(TARGET_MCU),STM32F1) -OPENOCD_TARGET ?= stm32f1x -else ifeq ($(TARGET_MCU),STM32F3) -OPENOCD_TARGET ?= stm32f3x -else ifeq ($(TARGET_MCU),STM32F4) -OPENOCD_TARGET ?= stm32f4x -else ifeq ($(TARGET_MCU),STM32F7) -OPENOCD_TARGET ?= stm32f7x +.PHONY: .FORCE openocd-cfg $(OPENOCD_CFG) openocd-run openocd-flash + +OPENOCD_CFG ?= $(TARGET_OBJ_DIR)/openocd.cfg +CLEAN_ARTIFACTS += $(OPENOCD_CFG) +OPENOCD_CMD ?= openocd + +STLINK ?= 2 + +ifeq ($(OPENOCD_INTERFACE),) +ifeq ($(STLINK),1) +OPENOCD_INTERFACE := stlink-v1 +else ifeq ($(STLINK),2) +OPENOCD_INTERFACE := stlink-v2 +else ifeq ($(STLINK),2.1) +OPENOCD_INTERFACE := stlink-v2-1 +else +$(error Uknown ST Link version $(STLINK)) +endif +endif + +ifeq ($(OPENOCD_TARGET),) +ifeq ($(TARGET_MCU_GROUP),STM32F3) +OPENOCD_TARGET := stm32f3x +else ifeq ($(TARGET_MCU_GROUP),STM32F4) +OPENOCD_TARGET := stm32f4x +else ifeq ($(TARGET_MCU_GROUP),STM32F7) +OPENOCD_TARGET := stm32f7x +endif endif ifeq ($(OPENOCD_TARGET),) $(warning Unknown OPENOCD_TARGET) endif -OPENOCD_CMDLINE := $(OPENOCD_CMD) -f interface/$(OPENOCD_INTERFACE).cfg -f target/$(OPENOCD_TARGET).cfg +OPENOCD_CMDLINE := $(OPENOCD_CMD) -f $(OPENOCD_CFG) + +openocd-cfg: $(OPENOCD_CFG) + +$(OPENOCD_CFG): .FORCE + $(V1) mkdir -p $(dir $@) + $(V1) echo "source [find interface/$(OPENOCD_INTERFACE).cfg]" > $@ + $(V1) echo "source [find target/$(OPENOCD_TARGET).cfg]" >> $@ -openocd-run: +openocd-run: $(OPENOCD_CFG) $(OPENOCD_CMDLINE) -openocd-flash: $(TARGET_ELF) +openocd-flash: $(TARGET_ELF) $(OPENOCD_CFG) (echo "halt; program $(realpath $<) verify reset" | nc -4 localhost 4444 2>/dev/null) || \ $(OPENOCD_CMDLINE) -c "program $< verify reset exit" From 494cd254d4098554e63eecd0fcdc4a36834a22fd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 4 Nov 2019 16:21:03 +0000 Subject: [PATCH 041/110] [DEVELOPMENT] Add svd Makefile target to generate SVD file for targets SVD are useful for some IDEs, to be able to see the state of all peripherals. --- Makefile | 5 +- dev/svd/STM32F303.svd | 40381 +++++++++++++++++++++++ dev/svd/STM32F405.svd | 61681 ++++++++++++++++++++++++++++++++++ dev/svd/STM32F411.svd | 27110 +++++++++++++++ dev/svd/STM32F427.svd | 63121 +++++++++++++++++++++++++++++++++++ dev/svd/STM32F446.svd | 57155 ++++++++++++++++++++++++++++++++ dev/svd/STM32F7x2.svd | 61861 ++++++++++++++++++++++++++++++++++ dev/svd/STM32F7x5.svd | 71136 ++++++++++++++++++++++++++++++++++++++++ dev/svd/STM32F7x6.svd | 70681 +++++++++++++++++++++++++++++++++++++++ make/svd.mk | 32 + make/targets.mk | 40 +- 11 files changed, 453192 insertions(+), 11 deletions(-) create mode 100644 dev/svd/STM32F303.svd create mode 100644 dev/svd/STM32F405.svd create mode 100644 dev/svd/STM32F411.svd create mode 100644 dev/svd/STM32F427.svd create mode 100644 dev/svd/STM32F446.svd create mode 100644 dev/svd/STM32F7x2.svd create mode 100644 dev/svd/STM32F7x5.svd create mode 100644 dev/svd/STM32F7x6.svd create mode 100644 make/svd.mk diff --git a/Makefile b/Makefile index ae41d6b1b56..1b015d486ae 100644 --- a/Makefile +++ b/Makefile @@ -110,7 +110,7 @@ CSOURCES := $(shell find $(SRC_DIR) -name '*.c') # start specific includes include $(ROOT)/make/mcu/STM32.mk -include $(ROOT)/make/mcu/$(TARGET_MCU).mk +include $(ROOT)/make/mcu/$(TARGET_MCU_GROUP).mk # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. ifeq ($(FLASH_SIZE),) @@ -123,7 +123,7 @@ endif # Configure devide and target-specific defines and compiler flags DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) -TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) -D$(TARGET) +TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) -D$(TARGET_MCU_GROUP) -D$(TARGET) ifneq ($(HSE_VALUE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) @@ -274,6 +274,7 @@ CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP) include $(ROOT)/make/stamp.mk include $(ROOT)/make/settings.mk +include $(ROOT)/make/svd.mk # Make sure build date and revision is updated on every incremental build $(TARGET_OBJ_DIR)/build/version.o : $(TARGET_SRC) diff --git a/dev/svd/STM32F303.svd b/dev/svd/STM32F303.svd new file mode 100644 index 00000000000..9c2909c9ef8 --- /dev/null +++ b/dev/svd/STM32F303.svd @@ -0,0 +1,40381 @@ + + + STM32F303 + 1.4 + STM32F303 + + + CM4 + r1p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + GPIOA + General-purpose I/Os + GPIO + 0x48000000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x28000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x24000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Lok Key + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + Port bit reset register + 0x28 + 0x20 + write-only + 0x00000000 + + + BR0 + Port x Reset bit y + 0 + 1 + + + BR1 + Port x Reset bit y + 1 + 1 + + + BR2 + Port x Reset bit y + 2 + 1 + + + BR3 + Port x Reset bit y + 3 + 1 + + + BR4 + Port x Reset bit y + 4 + 1 + + + BR5 + Port x Reset bit y + 5 + 1 + + + BR6 + Port x Reset bit y + 6 + 1 + + + BR7 + Port x Reset bit y + 7 + 1 + + + BR8 + Port x Reset bit y + 8 + 1 + + + BR9 + Port x Reset bit y + 9 + 1 + + + BR10 + Port x Reset bit y + 10 + 1 + + + BR11 + Port x Reset bit y + 11 + 1 + + + BR12 + Port x Reset bit y + 12 + 1 + + + BR13 + Port x Reset bit y + 13 + 1 + + + BR14 + Port x Reset bit y + 14 + 1 + + + BR15 + Port x Reset bit y + 15 + 1 + + + + + + + GPIOB + General-purpose I/Os + GPIO + 0x48000400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bit + 15 + 15 + 1 + + + OT14 + Port x configuration bit + 14 + 14 + 1 + + + OT13 + Port x configuration bit + 13 + 13 + 1 + + + OT12 + Port x configuration bit + 12 + 12 + 1 + + + OT11 + Port x configuration bit + 11 + 11 + 1 + + + OT10 + Port x configuration bit + 10 + 10 + 1 + + + OT9 + Port x configuration bit 9 + 9 + 1 + + + OT8 + Port x configuration bit 8 + 8 + 1 + + + OT7 + Port x configuration bit 7 + 7 + 1 + + + OT6 + Port x configuration bit 6 + 6 + 1 + + + OT5 + Port x configuration bit 5 + 5 + 1 + + + OT4 + Port x configuration bit 4 + 4 + 1 + + + OT3 + Port x configuration bit 3 + 3 + 1 + + + OT2 + Port x configuration bit 2 + 2 + 1 + + + OT1 + Port x configuration bit 1 + 1 + 1 + + + OT0 + Port x configuration bit 0 + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Lok Key + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + Port bit reset register + 0x28 + 0x20 + write-only + 0x00000000 + + + BR0 + Port x Reset bit y + 0 + 1 + + + BR1 + Port x Reset bit y + 1 + 1 + + + BR2 + Port x Reset bit y + 2 + 1 + + + BR3 + Port x Reset bit y + 3 + 1 + + + BR4 + Port x Reset bit y + 4 + 1 + + + BR5 + Port x Reset bit y + 5 + 1 + + + BR6 + Port x Reset bit y + 6 + 1 + + + BR7 + Port x Reset bit y + 7 + 1 + + + BR8 + Port x Reset bit y + 8 + 1 + + + BR9 + Port x Reset bit y + 9 + 1 + + + BR10 + Port x Reset bit y + 10 + 1 + + + BR11 + Port x Reset bit y + 11 + 1 + + + BR12 + Port x Reset bit y + 12 + 1 + + + BR13 + Port x Reset bit y + 13 + 1 + + + BR14 + Port x Reset bit y + 14 + 1 + + + BR15 + Port x Reset bit y + 15 + 1 + + + + + + + GPIOC + 0x48000800 + + + GPIOD + 0x48000C00 + + + GPIOE + 0x48001000 + + + GPIOF + 0x48001400 + + + GPIOG + 0x48001800 + + + GPIOH + 0x48001C00 + + + TSC + Touch sensing controller + TSC + 0x40024000 + + 0x0 + 0x400 + registers + + + EXTI2_TSC + EXTI Line2 and Touch sensing + interrupts + 8 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CTPH + Charge transfer pulse high + 28 + 4 + + + CTPL + Charge transfer pulse low + 24 + 4 + + + SSD + Spread spectrum deviation + 17 + 7 + + + SSE + Spread spectrum enable + 16 + 1 + + + SSPSC + Spread spectrum prescaler + 15 + 1 + + + PGPSC + pulse generator prescaler + 12 + 3 + + + MCV + Max count value + 5 + 3 + + + IODEF + I/O Default mode + 4 + 1 + + + SYNCPOL + Synchronization pin + polarity + 3 + 1 + + + AM + Acquisition mode + 2 + 1 + + + START + Start a new acquisition + 1 + 1 + + + TSCE + Touch sensing controller + enable + 0 + 1 + + + + + IER + IER + interrupt enable register + 0x4 + 0x20 + read-write + 0x00000000 + + + MCEIE + Max count error interrupt + enable + 1 + 1 + + + EOAIE + End of acquisition interrupt + enable + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x8 + 0x20 + read-write + 0x00000000 + + + MCEIC + Max count error interrupt + clear + 1 + 1 + + + EOAIC + End of acquisition interrupt + clear + 0 + 1 + + + + + ISR + ISR + interrupt status register + 0xC + 0x20 + read-write + 0x00000000 + + + MCEF + Max count error flag + 1 + 1 + + + EOAF + End of acquisition flag + 0 + 1 + + + + + IOHCR + IOHCR + I/O hysteresis control + register + 0x10 + 0x20 + read-write + 0xFFFFFFFF + + + G1_IO1 + G1_IO1 Schmitt trigger hysteresis + mode + 0 + 1 + + + G1_IO2 + G1_IO2 Schmitt trigger hysteresis + mode + 1 + 1 + + + G1_IO3 + G1_IO3 Schmitt trigger hysteresis + mode + 2 + 1 + + + G1_IO4 + G1_IO4 Schmitt trigger hysteresis + mode + 3 + 1 + + + G2_IO1 + G2_IO1 Schmitt trigger hysteresis + mode + 4 + 1 + + + G2_IO2 + G2_IO2 Schmitt trigger hysteresis + mode + 5 + 1 + + + G2_IO3 + G2_IO3 Schmitt trigger hysteresis + mode + 6 + 1 + + + G2_IO4 + G2_IO4 Schmitt trigger hysteresis + mode + 7 + 1 + + + G3_IO1 + G3_IO1 Schmitt trigger hysteresis + mode + 8 + 1 + + + G3_IO2 + G3_IO2 Schmitt trigger hysteresis + mode + 9 + 1 + + + G3_IO3 + G3_IO3 Schmitt trigger hysteresis + mode + 10 + 1 + + + G3_IO4 + G3_IO4 Schmitt trigger hysteresis + mode + 11 + 1 + + + G4_IO1 + G4_IO1 Schmitt trigger hysteresis + mode + 12 + 1 + + + G4_IO2 + G4_IO2 Schmitt trigger hysteresis + mode + 13 + 1 + + + G4_IO3 + G4_IO3 Schmitt trigger hysteresis + mode + 14 + 1 + + + G4_IO4 + G4_IO4 Schmitt trigger hysteresis + mode + 15 + 1 + + + G5_IO1 + G5_IO1 Schmitt trigger hysteresis + mode + 16 + 1 + + + G5_IO2 + G5_IO2 Schmitt trigger hysteresis + mode + 17 + 1 + + + G5_IO3 + G5_IO3 Schmitt trigger hysteresis + mode + 18 + 1 + + + G5_IO4 + G5_IO4 Schmitt trigger hysteresis + mode + 19 + 1 + + + G6_IO1 + G6_IO1 Schmitt trigger hysteresis + mode + 20 + 1 + + + G6_IO2 + G6_IO2 Schmitt trigger hysteresis + mode + 21 + 1 + + + G6_IO3 + G6_IO3 Schmitt trigger hysteresis + mode + 22 + 1 + + + G6_IO4 + G6_IO4 Schmitt trigger hysteresis + mode + 23 + 1 + + + G7_IO1 + G7_IO1 Schmitt trigger hysteresis + mode + 24 + 1 + + + G7_IO2 + G7_IO2 Schmitt trigger hysteresis + mode + 25 + 1 + + + G7_IO3 + G7_IO3 Schmitt trigger hysteresis + mode + 26 + 1 + + + G7_IO4 + G7_IO4 Schmitt trigger hysteresis + mode + 27 + 1 + + + G8_IO1 + G8_IO1 Schmitt trigger hysteresis + mode + 28 + 1 + + + G8_IO2 + G8_IO2 Schmitt trigger hysteresis + mode + 29 + 1 + + + G8_IO3 + G8_IO3 Schmitt trigger hysteresis + mode + 30 + 1 + + + G8_IO4 + G8_IO4 Schmitt trigger hysteresis + mode + 31 + 1 + + + + + IOASCR + IOASCR + I/O analog switch control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + G1_IO1 + G1_IO1 analog switch + enable + 0 + 1 + + + G1_IO2 + G1_IO2 analog switch + enable + 1 + 1 + + + G1_IO3 + G1_IO3 analog switch + enable + 2 + 1 + + + G1_IO4 + G1_IO4 analog switch + enable + 3 + 1 + + + G2_IO1 + G2_IO1 analog switch + enable + 4 + 1 + + + G2_IO2 + G2_IO2 analog switch + enable + 5 + 1 + + + G2_IO3 + G2_IO3 analog switch + enable + 6 + 1 + + + G2_IO4 + G2_IO4 analog switch + enable + 7 + 1 + + + G3_IO1 + G3_IO1 analog switch + enable + 8 + 1 + + + G3_IO2 + G3_IO2 analog switch + enable + 9 + 1 + + + G3_IO3 + G3_IO3 analog switch + enable + 10 + 1 + + + G3_IO4 + G3_IO4 analog switch + enable + 11 + 1 + + + G4_IO1 + G4_IO1 analog switch + enable + 12 + 1 + + + G4_IO2 + G4_IO2 analog switch + enable + 13 + 1 + + + G4_IO3 + G4_IO3 analog switch + enable + 14 + 1 + + + G4_IO4 + G4_IO4 analog switch + enable + 15 + 1 + + + G5_IO1 + G5_IO1 analog switch + enable + 16 + 1 + + + G5_IO2 + G5_IO2 analog switch + enable + 17 + 1 + + + G5_IO3 + G5_IO3 analog switch + enable + 18 + 1 + + + G5_IO4 + G5_IO4 analog switch + enable + 19 + 1 + + + G6_IO1 + G6_IO1 analog switch + enable + 20 + 1 + + + G6_IO2 + G6_IO2 analog switch + enable + 21 + 1 + + + G6_IO3 + G6_IO3 analog switch + enable + 22 + 1 + + + G6_IO4 + G6_IO4 analog switch + enable + 23 + 1 + + + G7_IO1 + G7_IO1 analog switch + enable + 24 + 1 + + + G7_IO2 + G7_IO2 analog switch + enable + 25 + 1 + + + G7_IO3 + G7_IO3 analog switch + enable + 26 + 1 + + + G7_IO4 + G7_IO4 analog switch + enable + 27 + 1 + + + G8_IO1 + G8_IO1 analog switch + enable + 28 + 1 + + + G8_IO2 + G8_IO2 analog switch + enable + 29 + 1 + + + G8_IO3 + G8_IO3 analog switch + enable + 30 + 1 + + + G8_IO4 + G8_IO4 analog switch + enable + 31 + 1 + + + + + IOSCR + IOSCR + I/O sampling control register + 0x20 + 0x20 + read-write + 0x00000000 + + + G1_IO1 + G1_IO1 sampling mode + 0 + 1 + + + G1_IO2 + G1_IO2 sampling mode + 1 + 1 + + + G1_IO3 + G1_IO3 sampling mode + 2 + 1 + + + G1_IO4 + G1_IO4 sampling mode + 3 + 1 + + + G2_IO1 + G2_IO1 sampling mode + 4 + 1 + + + G2_IO2 + G2_IO2 sampling mode + 5 + 1 + + + G2_IO3 + G2_IO3 sampling mode + 6 + 1 + + + G2_IO4 + G2_IO4 sampling mode + 7 + 1 + + + G3_IO1 + G3_IO1 sampling mode + 8 + 1 + + + G3_IO2 + G3_IO2 sampling mode + 9 + 1 + + + G3_IO3 + G3_IO3 sampling mode + 10 + 1 + + + G3_IO4 + G3_IO4 sampling mode + 11 + 1 + + + G4_IO1 + G4_IO1 sampling mode + 12 + 1 + + + G4_IO2 + G4_IO2 sampling mode + 13 + 1 + + + G4_IO3 + G4_IO3 sampling mode + 14 + 1 + + + G4_IO4 + G4_IO4 sampling mode + 15 + 1 + + + G5_IO1 + G5_IO1 sampling mode + 16 + 1 + + + G5_IO2 + G5_IO2 sampling mode + 17 + 1 + + + G5_IO3 + G5_IO3 sampling mode + 18 + 1 + + + G5_IO4 + G5_IO4 sampling mode + 19 + 1 + + + G6_IO1 + G6_IO1 sampling mode + 20 + 1 + + + G6_IO2 + G6_IO2 sampling mode + 21 + 1 + + + G6_IO3 + G6_IO3 sampling mode + 22 + 1 + + + G6_IO4 + G6_IO4 sampling mode + 23 + 1 + + + G7_IO1 + G7_IO1 sampling mode + 24 + 1 + + + G7_IO2 + G7_IO2 sampling mode + 25 + 1 + + + G7_IO3 + G7_IO3 sampling mode + 26 + 1 + + + G7_IO4 + G7_IO4 sampling mode + 27 + 1 + + + G8_IO1 + G8_IO1 sampling mode + 28 + 1 + + + G8_IO2 + G8_IO2 sampling mode + 29 + 1 + + + G8_IO3 + G8_IO3 sampling mode + 30 + 1 + + + G8_IO4 + G8_IO4 sampling mode + 31 + 1 + + + + + IOCCR + IOCCR + I/O channel control register + 0x28 + 0x20 + read-write + 0x00000000 + + + G1_IO1 + G1_IO1 channel mode + 0 + 1 + + + G1_IO2 + G1_IO2 channel mode + 1 + 1 + + + G1_IO3 + G1_IO3 channel mode + 2 + 1 + + + G1_IO4 + G1_IO4 channel mode + 3 + 1 + + + G2_IO1 + G2_IO1 channel mode + 4 + 1 + + + G2_IO2 + G2_IO2 channel mode + 5 + 1 + + + G2_IO3 + G2_IO3 channel mode + 6 + 1 + + + G2_IO4 + G2_IO4 channel mode + 7 + 1 + + + G3_IO1 + G3_IO1 channel mode + 8 + 1 + + + G3_IO2 + G3_IO2 channel mode + 9 + 1 + + + G3_IO3 + G3_IO3 channel mode + 10 + 1 + + + G3_IO4 + G3_IO4 channel mode + 11 + 1 + + + G4_IO1 + G4_IO1 channel mode + 12 + 1 + + + G4_IO2 + G4_IO2 channel mode + 13 + 1 + + + G4_IO3 + G4_IO3 channel mode + 14 + 1 + + + G4_IO4 + G4_IO4 channel mode + 15 + 1 + + + G5_IO1 + G5_IO1 channel mode + 16 + 1 + + + G5_IO2 + G5_IO2 channel mode + 17 + 1 + + + G5_IO3 + G5_IO3 channel mode + 18 + 1 + + + G5_IO4 + G5_IO4 channel mode + 19 + 1 + + + G6_IO1 + G6_IO1 channel mode + 20 + 1 + + + G6_IO2 + G6_IO2 channel mode + 21 + 1 + + + G6_IO3 + G6_IO3 channel mode + 22 + 1 + + + G6_IO4 + G6_IO4 channel mode + 23 + 1 + + + G7_IO1 + G7_IO1 channel mode + 24 + 1 + + + G7_IO2 + G7_IO2 channel mode + 25 + 1 + + + G7_IO3 + G7_IO3 channel mode + 26 + 1 + + + G7_IO4 + G7_IO4 channel mode + 27 + 1 + + + G8_IO1 + G8_IO1 channel mode + 28 + 1 + + + G8_IO2 + G8_IO2 channel mode + 29 + 1 + + + G8_IO3 + G8_IO3 channel mode + 30 + 1 + + + G8_IO4 + G8_IO4 channel mode + 31 + 1 + + + + + IOGCSR + IOGCSR + I/O group control status + register + 0x30 + 0x20 + 0x00000000 + + + G8S + Analog I/O group x status + 23 + 1 + read-write + + + G7S + Analog I/O group x status + 22 + 1 + read-write + + + G6S + Analog I/O group x status + 21 + 1 + read-only + + + G5S + Analog I/O group x status + 20 + 1 + read-only + + + G4S + Analog I/O group x status + 19 + 1 + read-only + + + G3S + Analog I/O group x status + 18 + 1 + read-only + + + G2S + Analog I/O group x status + 17 + 1 + read-only + + + G1S + Analog I/O group x status + 16 + 1 + read-only + + + G8E + Analog I/O group x enable + 7 + 1 + read-write + + + G7E + Analog I/O group x enable + 6 + 1 + read-write + + + G6E + Analog I/O group x enable + 5 + 1 + read-write + + + G5E + Analog I/O group x enable + 4 + 1 + read-write + + + G4E + Analog I/O group x enable + 3 + 1 + read-write + + + G3E + Analog I/O group x enable + 2 + 1 + read-write + + + G2E + Analog I/O group x enable + 1 + 1 + read-write + + + G1E + Analog I/O group x enable + 0 + 1 + read-write + + + + + IOG1CR + IOG1CR + I/O group x counter register + 0x34 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG2CR + IOG2CR + I/O group x counter register + 0x38 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG3CR + IOG3CR + I/O group x counter register + 0x3C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG4CR + IOG4CR + I/O group x counter register + 0x40 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG5CR + IOG5CR + I/O group x counter register + 0x44 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG6CR + IOG6CR + I/O group x counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG7CR + IOG7CR + I/O group x counter register + 0x4C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + IOG8CR + IOG8CR + I/O group x counter register + 0x50 + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 14 + + + + + + + CRC + cyclic redundancy check calculation + unit + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data register bits + 0 + 32 + + + + + IDR + IDR + Independent data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + General-purpose 8-bit data register + bits + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + read-write + 0x00000000 + + + RESET + reset bit + 0 + 1 + + + POLYSIZE + Polynomial size + 3 + 2 + + + REV_IN + Reverse input data + 5 + 2 + + + REV_OUT + Reverse output data + 7 + 1 + + + + + INIT + INIT + Initial CRC value + 0x10 + 0x20 + read-write + 0xFFFFFFFF + + + INIT + Programmable initial CRC + value + 0 + 32 + + + + + POL + POL + CRC polynomial + 0x14 + 0x20 + read-write + 0x04C11DB7 + + + POL + Programmable polynomial + 0 + 32 + + + + + + + Flash + Flash + Flash + 0x40022000 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + 0x00000030 + + + LATENCY + LATENCY + 0 + 3 + read-write + + + PRFTBE + PRFTBE + 4 + 1 + read-write + + + PRFTBS + PRFTBS + 5 + 1 + read-only + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + FKEYR + Flash Key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEYR + Option byte key + 0 + 32 + + + + + SR + SR + Flash status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 5 + 1 + read-write + + + WRPRT + Write protection error + 4 + 1 + read-write + + + PGERR + Programming error + 2 + 1 + read-write + + + BSY + Busy + 0 + 1 + read-only + + + + + CR + CR + Flash control register + 0x10 + 0x20 + read-write + 0x00000080 + + + FORCE_OPTLOAD + Force option byte loading + 13 + 1 + + + EOPIE + End of operation interrupt + enable + 12 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + OPTWRE + Option bytes write enable + 9 + 1 + + + LOCK + Lock + 7 + 1 + + + STRT + Start + 6 + 1 + + + OPTER + Option byte erase + 5 + 1 + + + OPTPG + Option byte programming + 4 + 1 + + + MER + Mass erase + 2 + 1 + + + PER + Page erase + 1 + 1 + + + PG + Programming + 0 + 1 + + + + + AR + AR + Flash address register + 0x14 + 0x20 + write-only + 0x00000000 + + + FAR + Flash address + 0 + 32 + + + + + OBR + OBR + Option byte register + 0x1C + 0x20 + read-only + 0xFFFFFF02 + + + OPTERR + Option byte error + 0 + 1 + + + LEVEL1_PROT + Level 1 protection status + 1 + 1 + + + LEVEL2_PROT + Level 2 protection status + 2 + 1 + + + WDG_SW + WDG_SW + 8 + 1 + + + nRST_STOP + nRST_STOP + 9 + 1 + + + nRST_STDBY + nRST_STDBY + 10 + 1 + + + BOOT1 + BOOT1 + 12 + 1 + + + VDDA_MONITOR + VDDA_MONITOR + 13 + 1 + + + SRAM_PARITY_CHECK + SRAM_PARITY_CHECK + 14 + 1 + + + Data0 + Data0 + 16 + 8 + + + Data1 + Data1 + 24 + 8 + + + + + WRPR + WRPR + Write protection register + 0x20 + 0x20 + read-only + 0xFFFFFFFF + + + WRP + Write protect + 0 + 32 + + + + + + + RCC + Reset and clock control + RCC + 0x40021000 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + Clock control register + 0x0 + 0x20 + 0x00000083 + + + HSION + Internal High Speed clock + enable + 0 + 1 + read-write + + + HSIRDY + Internal High Speed clock ready + flag + 1 + 1 + read-only + + + HSITRIM + Internal High Speed clock + trimming + 3 + 5 + read-write + + + HSICAL + Internal High Speed clock + Calibration + 8 + 8 + read-only + + + HSEON + External High Speed clock + enable + 16 + 1 + read-write + + + HSERDY + External High Speed clock ready + flag + 17 + 1 + read-only + + + HSEBYP + External High Speed clock + Bypass + 18 + 1 + read-write + + + CSSON + Clock Security System + enable + 19 + 1 + read-write + + + PLLON + PLL enable + 24 + 1 + read-write + + + PLLRDY + PLL clock ready flag + 25 + 1 + read-only + + + + + CFGR + CFGR + Clock configuration register + (RCC_CFGR) + 0x4 + 0x20 + 0x00000000 + + + SW + System clock Switch + 0 + 2 + read-write + + + SWS + System Clock Switch Status + 2 + 2 + read-only + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 8 + 3 + read-write + + + PPRE2 + APB high speed prescaler + (APB2) + 11 + 3 + read-write + + + PLLSRC + PLL entry clock source + 15 + 2 + read-write + + + PLLXTPRE + HSE divider for PLL entry + 17 + 1 + read-write + + + PLLMUL + PLL Multiplication Factor + 18 + 4 + read-write + + + USBPRES + USB prescaler + 22 + 1 + read-write + + + MCO + Microcontroller clock + output + 24 + 3 + read-write + + + MCOF + Microcontroller Clock Output + Flag + 28 + 1 + read-only + + + I2SSRC + I2S external clock source + selection + 23 + 1 + read-write + + + + + CIR + CIR + Clock interrupt register + (RCC_CIR) + 0x8 + 0x20 + 0x00000000 + + + LSIRDYF + LSI Ready Interrupt flag + 0 + 1 + read-only + + + LSERDYF + LSE Ready Interrupt flag + 1 + 1 + read-only + + + HSIRDYF + HSI Ready Interrupt flag + 2 + 1 + read-only + + + HSERDYF + HSE Ready Interrupt flag + 3 + 1 + read-only + + + PLLRDYF + PLL Ready Interrupt flag + 4 + 1 + read-only + + + CSSF + Clock Security System Interrupt + flag + 7 + 1 + read-only + + + LSIRDYIE + LSI Ready Interrupt Enable + 8 + 1 + read-write + + + LSERDYIE + LSE Ready Interrupt Enable + 9 + 1 + read-write + + + HSIRDYIE + HSI Ready Interrupt Enable + 10 + 1 + read-write + + + HSERDYIE + HSE Ready Interrupt Enable + 11 + 1 + read-write + + + PLLRDYIE + PLL Ready Interrupt Enable + 12 + 1 + read-write + + + LSIRDYC + LSI Ready Interrupt Clear + 16 + 1 + write-only + + + LSERDYC + LSE Ready Interrupt Clear + 17 + 1 + write-only + + + HSIRDYC + HSI Ready Interrupt Clear + 18 + 1 + write-only + + + HSERDYC + HSE Ready Interrupt Clear + 19 + 1 + write-only + + + PLLRDYC + PLL Ready Interrupt Clear + 20 + 1 + write-only + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + (RCC_APB2RSTR) + 0xC + 0x20 + read-write + 0x00000000 + + + SYSCFGRST + SYSCFG and COMP reset + 0 + 1 + + + TIM1RST + TIM1 timer reset + 11 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + TIM8RST + TIM8 timer reset + 13 + 1 + + + USART1RST + USART1 reset + 14 + 1 + + + TIM15RST + TIM15 timer reset + 16 + 1 + + + TIM16RST + TIM16 timer reset + 17 + 1 + + + TIM17RST + TIM17 timer reset + 18 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + (RCC_APB1RSTR) + 0x10 + 0x20 + read-write + 0x00000000 + + + TIM2RST + Timer 2 reset + 0 + 1 + + + TIM3RST + Timer 3 reset + 1 + 1 + + + TIM4RST + Timer 14 reset + 2 + 1 + + + TIM6RST + Timer 6 reset + 4 + 1 + + + TIM7RST + Timer 7 reset + 5 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI2 reset + 14 + 1 + + + SPI3RST + SPI3 reset + 15 + 1 + + + USART2RST + USART 2 reset + 17 + 1 + + + USART3RST + USART3 reset + 18 + 1 + + + UART4RST + UART 4 reset + 19 + 1 + + + UART5RST + UART 5 reset + 20 + 1 + + + I2C1RST + I2C1 reset + 21 + 1 + + + I2C2RST + I2C2 reset + 22 + 1 + + + USBRST + USB reset + 23 + 1 + + + CANRST + CAN reset + 25 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC interface reset + 29 + 1 + + + I2C3RST + I2C3 reset + 30 + 1 + + + + + AHBENR + AHBENR + AHB Peripheral Clock enable register + (RCC_AHBENR) + 0x14 + 0x20 + read-write + 0x00000014 + + + DMAEN + DMA1 clock enable + 0 + 1 + + + DMA2EN + DMA2 clock enable + 1 + 1 + + + SRAMEN + SRAM interface clock + enable + 2 + 1 + + + FLITFEN + FLITF clock enable + 4 + 1 + + + FMCEN + FMC clock enable + 5 + 1 + + + CRCEN + CRC clock enable + 6 + 1 + + + IOPHEN + IO port H clock enable + 16 + 1 + + + IOPAEN + I/O port A clock enable + 17 + 1 + + + IOPBEN + I/O port B clock enable + 18 + 1 + + + IOPCEN + I/O port C clock enable + 19 + 1 + + + IOPDEN + I/O port D clock enable + 20 + 1 + + + IOPEEN + I/O port E clock enable + 21 + 1 + + + IOPFEN + I/O port F clock enable + 22 + 1 + + + IOPGEN + I/O port G clock enable + 23 + 1 + + + TSCEN + Touch sensing controller clock + enable + 24 + 1 + + + ADC12EN + ADC1 and ADC2 clock enable + 28 + 1 + + + ADC34EN + ADC3 and ADC4 clock enable + 29 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable register + (RCC_APB2ENR) + 0x18 + 0x20 + read-write + 0x00000000 + + + SYSCFGEN + SYSCFG clock enable + 0 + 1 + + + TIM1EN + TIM1 Timer clock enable + 11 + 1 + + + SPI1EN + SPI 1 clock enable + 12 + 1 + + + TIM8EN + TIM8 Timer clock enable + 13 + 1 + + + USART1EN + USART1 clock enable + 14 + 1 + + + TIM15EN + TIM15 timer clock enable + 16 + 1 + + + TIM16EN + TIM16 timer clock enable + 17 + 1 + + + TIM17EN + TIM17 timer clock enable + 18 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable register + (RCC_APB1ENR) + 0x1C + 0x20 + read-write + 0x00000000 + + + TIM2EN + Timer 2 clock enable + 0 + 1 + + + TIM3EN + Timer 3 clock enable + 1 + 1 + + + TIM4EN + Timer 4 clock enable + 2 + 1 + + + TIM6EN + Timer 6 clock enable + 4 + 1 + + + TIM7EN + Timer 7 clock enable + 5 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI 2 clock enable + 14 + 1 + + + SPI3EN + SPI 3 clock enable + 15 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART 3 clock enable + 18 + 1 + + + USART4EN + USART 4 clock enable + 19 + 1 + + + USART5EN + USART 5 clock enable + 20 + 1 + + + I2C1EN + I2C 1 clock enable + 21 + 1 + + + I2C2EN + I2C 2 clock enable + 22 + 1 + + + USBEN + USB clock enable + 23 + 1 + + + CANEN + CAN clock enable + 25 + 1 + + + DAC2EN + DAC2 interface clock + enable + 26 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + I2C3EN + I2C3 clock enable + 30 + 1 + + + + + BDCR + BDCR + Backup domain control register + (RCC_BDCR) + 0x20 + 0x20 + 0x00000000 + + + LSEON + External Low Speed oscillator + enable + 0 + 1 + read-write + + + LSERDY + External Low Speed oscillator + ready + 1 + 1 + read-only + + + LSEBYP + External Low Speed oscillator + bypass + 2 + 1 + read-write + + + LSEDRV + LSE oscillator drive + capability + 3 + 2 + read-write + + + RTCSEL + RTC clock source selection + 8 + 2 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + + + CSR + CSR + Control/status register + (RCC_CSR) + 0x24 + 0x20 + 0x0C000000 + + + LSION + Internal low speed oscillator + enable + 0 + 1 + read-write + + + LSIRDY + Internal low speed oscillator + ready + 1 + 1 + read-only + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + OBLRSTF + Option byte loader reset + flag + 25 + 1 + read-write + + + PINRSTF + PIN reset flag + 26 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + IWDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + + + AHBRSTR + AHBRSTR + AHB peripheral reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + FMCRST + FMC reset + 5 + 1 + + + IOPHRST + I/O port H reset + 16 + 1 + + + IOPARST + I/O port A reset + 17 + 1 + + + IOPBRST + I/O port B reset + 18 + 1 + + + IOPCRST + I/O port C reset + 19 + 1 + + + IOPDRST + I/O port D reset + 20 + 1 + + + IOPERST + I/O port E reset + 21 + 1 + + + IOPFRST + I/O port F reset + 22 + 1 + + + IOPGRST + Touch sensing controller + reset + 23 + 1 + + + TSCRST + Touch sensing controller + reset + 24 + 1 + + + ADC12RST + ADC1 and ADC2 reset + 28 + 1 + + + ADC34RST + ADC3 and ADC4 reset + 29 + 1 + + + + + CFGR2 + CFGR2 + Clock configuration register 2 + 0x2C + 0x20 + read-write + 0x00000000 + + + PREDIV + PREDIV division factor + 0 + 4 + + + ADC12PRES + ADC1 and ADC2 prescaler + 4 + 5 + + + ADC34PRES + ADC3 and ADC4 prescaler + 9 + 5 + + + + + CFGR3 + CFGR3 + Clock configuration register 3 + 0x30 + 0x20 + read-write + 0x00000000 + + + USART1SW + USART1 clock source + selection + 0 + 2 + + + I2C1SW + I2C1 clock source + selection + 4 + 1 + + + I2C2SW + I2C2 clock source + selection + 5 + 1 + + + I2C3SW + I2C3 clock source + selection + 6 + 1 + + + USART2SW + USART2 clock source + selection + 16 + 2 + + + USART3SW + USART3 clock source + selection + 18 + 2 + + + TIM1SW + Timer1 clock source + selection + 8 + 1 + + + TIM8SW + Timer8 clock source + selection + 9 + 1 + + + UART4SW + UART4 clock source + selection + 20 + 2 + + + UART5SW + UART5 clock source + selection + 22 + 2 + + + + + + + DMA1 + DMA controller 1 + DMA + 0x40020000 + + 0x0 + 0x400 + registers + + + DMA1_CH1 + DMA1 channel 1 interrupt + 11 + + + DMA1_CH2 + DMA1 channel 2 interrupt + 12 + + + DMA1_CH3 + DMA1 channel 3 interrupt + 13 + + + DMA1_CH4 + DMA1 channel 4 interrupt + 14 + + + DMA1_CH5 + DMA1 channel 5 interrupt + 15 + + + DMA1_CH6 + DMA1 channel 6 interrupt + 16 + + + DMA1_CH7 + DMA1 channel 7interrupt + 17 + + + + ISR + ISR + DMA interrupt status register + (DMA_ISR) + 0x0 + 0x20 + read-only + 0x00000000 + + + GIF1 + Channel 1 Global interrupt + flag + 0 + 1 + + + TCIF1 + Channel 1 Transfer Complete + flag + 1 + 1 + + + HTIF1 + Channel 1 Half Transfer Complete + flag + 2 + 1 + + + TEIF1 + Channel 1 Transfer Error + flag + 3 + 1 + + + GIF2 + Channel 2 Global interrupt + flag + 4 + 1 + + + TCIF2 + Channel 2 Transfer Complete + flag + 5 + 1 + + + HTIF2 + Channel 2 Half Transfer Complete + flag + 6 + 1 + + + TEIF2 + Channel 2 Transfer Error + flag + 7 + 1 + + + GIF3 + Channel 3 Global interrupt + flag + 8 + 1 + + + TCIF3 + Channel 3 Transfer Complete + flag + 9 + 1 + + + HTIF3 + Channel 3 Half Transfer Complete + flag + 10 + 1 + + + TEIF3 + Channel 3 Transfer Error + flag + 11 + 1 + + + GIF4 + Channel 4 Global interrupt + flag + 12 + 1 + + + TCIF4 + Channel 4 Transfer Complete + flag + 13 + 1 + + + HTIF4 + Channel 4 Half Transfer Complete + flag + 14 + 1 + + + TEIF4 + Channel 4 Transfer Error + flag + 15 + 1 + + + GIF5 + Channel 5 Global interrupt + flag + 16 + 1 + + + TCIF5 + Channel 5 Transfer Complete + flag + 17 + 1 + + + HTIF5 + Channel 5 Half Transfer Complete + flag + 18 + 1 + + + TEIF5 + Channel 5 Transfer Error + flag + 19 + 1 + + + GIF6 + Channel 6 Global interrupt + flag + 20 + 1 + + + TCIF6 + Channel 6 Transfer Complete + flag + 21 + 1 + + + HTIF6 + Channel 6 Half Transfer Complete + flag + 22 + 1 + + + TEIF6 + Channel 6 Transfer Error + flag + 23 + 1 + + + GIF7 + Channel 7 Global interrupt + flag + 24 + 1 + + + TCIF7 + Channel 7 Transfer Complete + flag + 25 + 1 + + + HTIF7 + Channel 7 Half Transfer Complete + flag + 26 + 1 + + + TEIF7 + Channel 7 Transfer Error + flag + 27 + 1 + + + + + IFCR + IFCR + DMA interrupt flag clear register + (DMA_IFCR) + 0x4 + 0x20 + write-only + 0x00000000 + + + CGIF1 + Channel 1 Global interrupt + clear + 0 + 1 + + + CTCIF1 + Channel 1 Transfer Complete + clear + 1 + 1 + + + CHTIF1 + Channel 1 Half Transfer + clear + 2 + 1 + + + CTEIF1 + Channel 1 Transfer Error + clear + 3 + 1 + + + CGIF2 + Channel 2 Global interrupt + clear + 4 + 1 + + + CTCIF2 + Channel 2 Transfer Complete + clear + 5 + 1 + + + CHTIF2 + Channel 2 Half Transfer + clear + 6 + 1 + + + CTEIF2 + Channel 2 Transfer Error + clear + 7 + 1 + + + CGIF3 + Channel 3 Global interrupt + clear + 8 + 1 + + + CTCIF3 + Channel 3 Transfer Complete + clear + 9 + 1 + + + CHTIF3 + Channel 3 Half Transfer + clear + 10 + 1 + + + CTEIF3 + Channel 3 Transfer Error + clear + 11 + 1 + + + CGIF4 + Channel 4 Global interrupt + clear + 12 + 1 + + + CTCIF4 + Channel 4 Transfer Complete + clear + 13 + 1 + + + CHTIF4 + Channel 4 Half Transfer + clear + 14 + 1 + + + CTEIF4 + Channel 4 Transfer Error + clear + 15 + 1 + + + CGIF5 + Channel 5 Global interrupt + clear + 16 + 1 + + + CTCIF5 + Channel 5 Transfer Complete + clear + 17 + 1 + + + CHTIF5 + Channel 5 Half Transfer + clear + 18 + 1 + + + CTEIF5 + Channel 5 Transfer Error + clear + 19 + 1 + + + CGIF6 + Channel 6 Global interrupt + clear + 20 + 1 + + + CTCIF6 + Channel 6 Transfer Complete + clear + 21 + 1 + + + CHTIF6 + Channel 6 Half Transfer + clear + 22 + 1 + + + CTEIF6 + Channel 6 Transfer Error + clear + 23 + 1 + + + CGIF7 + Channel 7 Global interrupt + clear + 24 + 1 + + + CTCIF7 + Channel 7 Transfer Complete + clear + 25 + 1 + + + CHTIF7 + Channel 7 Half Transfer + clear + 26 + 1 + + + CTEIF7 + Channel 7 Transfer Error + clear + 27 + 1 + + + + + CCR1 + CCR1 + DMA channel configuration register + (DMA_CCR) + 0x8 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR1 + CNDTR1 + DMA channel 1 number of data + register + 0xC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR1 + CPAR1 + DMA channel 1 peripheral address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR1 + CMAR1 + DMA channel 1 memory address + register + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR2 + CCR2 + DMA channel configuration register + (DMA_CCR) + 0x1C + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR2 + CNDTR2 + DMA channel 2 number of data + register + 0x20 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR2 + CPAR2 + DMA channel 2 peripheral address + register + 0x24 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR2 + CMAR2 + DMA channel 2 memory address + register + 0x28 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR3 + CCR3 + DMA channel configuration register + (DMA_CCR) + 0x30 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR3 + CNDTR3 + DMA channel 3 number of data + register + 0x34 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR3 + CPAR3 + DMA channel 3 peripheral address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR3 + CMAR3 + DMA channel 3 memory address + register + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR4 + CCR4 + DMA channel configuration register + (DMA_CCR) + 0x44 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR4 + CNDTR4 + DMA channel 4 number of data + register + 0x48 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR4 + CPAR4 + DMA channel 4 peripheral address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR4 + CMAR4 + DMA channel 4 memory address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR5 + CCR5 + DMA channel configuration register + (DMA_CCR) + 0x58 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR5 + CNDTR5 + DMA channel 5 number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR5 + CPAR5 + DMA channel 5 peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR5 + CMAR5 + DMA channel 5 memory address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR6 + CCR6 + DMA channel configuration register + (DMA_CCR) + 0x6C + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR6 + CNDTR6 + DMA channel 6 number of data + register + 0x70 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR6 + CPAR6 + DMA channel 6 peripheral address + register + 0x74 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR6 + CMAR6 + DMA channel 6 memory address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + CCR7 + CCR7 + DMA channel configuration register + (DMA_CCR) + 0x80 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable + 0 + 1 + + + TCIE + Transfer complete interrupt + enable + 1 + 1 + + + HTIE + Half Transfer interrupt + enable + 2 + 1 + + + TEIE + Transfer error interrupt + enable + 3 + 1 + + + DIR + Data transfer direction + 4 + 1 + + + CIRC + Circular mode + 5 + 1 + + + PINC + Peripheral increment mode + 6 + 1 + + + MINC + Memory increment mode + 7 + 1 + + + PSIZE + Peripheral size + 8 + 2 + + + MSIZE + Memory size + 10 + 2 + + + PL + Channel Priority level + 12 + 2 + + + MEM2MEM + Memory to memory mode + 14 + 1 + + + + + CNDTR7 + CNDTR7 + DMA channel 7 number of data + register + 0x84 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer + 0 + 16 + + + + + CPAR7 + CPAR7 + DMA channel 7 peripheral address + register + 0x88 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + CMAR7 + CMAR7 + DMA channel 7 memory address + register + 0x8C + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + + + DMA2 + 0x40020400 + + DMA2_CH1 + DMA2 channel1 global interrupt + 56 + + + DMA2_CH2 + DMA2 channel2 global interrupt + 57 + + + DMA2_CH3 + DMA2 channel3 global interrupt + 58 + + + DMA2_CH4 + DMA2 channel4 global interrupt + 59 + + + DMA2_CH5 + DMA2 channel5 global interrupt + 60 + + + + TIM2 + General purpose timer + TIMs + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + DIR + Direction + 4 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + OCCS + OCREF clear selection + 3 + 1 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave mode selection bit3 + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output compare 1 fast + enable + 2 + 1 + + + OC1PE + Output compare 1 preload + enable + 3 + 1 + + + OC1M + Output compare 1 mode + 4 + 3 + + + OC1CE + Output compare 1 clear + enable + 7 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC2FE + Output compare 2 fast + enable + 10 + 1 + + + OC2PE + Output compare 2 preload + enable + 11 + 1 + + + OC2M + Output compare 2 mode + 12 + 3 + + + OC2CE + Output compare 2 clear + enable + 15 + 1 + + + OC1M_3 + Output compare 1 mode bit + 3 + 16 + 1 + + + OC2M_3 + Output compare 2 mode bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PSC + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + O24CE + Output compare 4 clear + enable + 15 + 1 + + + OC3M_3 + Output compare 3 mode bit3 + 16 + 1 + + + OC4M_3 + Output compare 4 mode bit3 + 24 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4NP + Capture/Compare 3 output + Polarity + 15 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNTL + Low counter value + 0 + 16 + + + CNTH + High counter value + 16 + 15 + + + CNT_or_UIFCPY + if IUFREMAP=0 than CNT with read write + access else UIFCPY with read only + access + 31 + 1 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARRL + Low Auto-reload value + 0 + 16 + + + ARRH + High Auto-reload value + 16 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1L + Low Capture/Compare 1 + value + 0 + 16 + + + CCR1H + High Capture/Compare 1 value (on + TIM2) + 16 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2L + Low Capture/Compare 2 + value + 0 + 16 + + + CCR2H + High Capture/Compare 2 value (on + TIM2) + 16 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3L + Low Capture/Compare value + 0 + 16 + + + CCR3H + High Capture/Compare value (on + TIM2) + 16 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4L + Low Capture/Compare value + 0 + 16 + + + CCR4H + High Capture/Compare value (on + TIM2) + 16 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM3 + 0x40000400 + + TIM3 + TIM3 global interrupt + 29 + + + + TIM4 + 0x40000800 + + TIM4 + TIM4 global interrupt + 30 + + + + TIM15 + General purpose timers + TIMs + 0x40014000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM15 + TIM1 Break/TIM15 global + interruts + 24 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + MMS + Master mode selection + 4 + 3 + + + TI1S + TI1 selection + 7 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + SMS_3 + Slave mode selection bit 3 + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + TDE + Trigger DMA request enable + 14 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC1M_3 + Output Compare 1 mode bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PSC + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM16 + General-purpose-timers + TIMs + 0x40014400 + + 0x0 + 0x400 + registers + + + TIM1_UP_TIM16 + TIM1 Update/TIM16 global + interrupts + 25 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + TDE + Trigger DMA request enable + 14 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1M_3 + Output Compare 1 mode + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x0000 + + + + + TIM17 + General purpose timer + TIMs + 0x40014800 + + 0x0 + 0x400 + registers + + + TIM1_TRG_COM_TIM17 + TIM1 trigger and commutation/TIM17 + interrupts + 26 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + TDE + Trigger DMA request enable + 14 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1M_3 + Output Compare 1 mode + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40013800 + + 0x0 + 0x400 + registers + + + USART1_EXTI25 + USART1 global interrupt and EXTI Line 25 + interrupt + 37 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT + Driver Enable assertion + time + 21 + 5 + + + DEDT + Driver Enable deassertion + time + 16 + 5 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UESM + USART enable in Stop mode + 1 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4 + Address of the USART node + 28 + 4 + + + ADD0 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD + Auto baud rate mode + 21 + 2 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + DATAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + WUFIE + Wakeup from Stop mode interrupt + enable + 22 + 1 + + + WUS + Wakeup from Stop mode interrupt flag + selection + 20 + 2 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + read-write + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + REACK + Receive enable acknowledge + flag + 22 + 1 + + + TEACK + Transmit enable acknowledge + flag + 21 + 1 + + + WUF + Wakeup from Stop mode flag + 20 + 1 + + + RWU + Receiver wakeup from Mute + mode + 19 + 1 + + + SBKF + Send break flag + 18 + 1 + + + CMF + character match flag + 17 + 1 + + + BUSY + Busy flag + 16 + 1 + + + ABRF + Auto baud rate flag + 15 + 1 + + + ABRE + Auto baud rate error + 14 + 1 + + + EOBF + End of block flag + 12 + 1 + + + RTOF + Receiver timeout + 11 + 1 + + + CTS + CTS flag + 10 + 1 + + + CTSIF + CTS interrupt flag + 9 + 1 + + + LBDF + LIN break detection flag + 8 + 1 + + + TXE + Transmit data register + empty + 7 + 1 + + + TC + Transmission complete + 6 + 1 + + + RXNE + Read data register not + empty + 5 + 1 + + + IDLE + Idle line detected + 4 + 1 + + + ORE + Overrun error + 3 + 1 + + + NF + Noise detected flag + 2 + 1 + + + FE + Framing error + 1 + 1 + + + PE + Parity error + 0 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + read-write + 0x0000 + + + WUCF + Wakeup from Stop mode clear + flag + 20 + 1 + + + CMCF + Character match clear flag + 17 + 1 + + + EOBCF + End of timeout clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + + + USART2 + 0x40004400 + + USART2_EXTI26 + USART2 global interrupt and EXTI Line 26 + interrupt + 38 + + + + USART3 + 0x40004800 + + USART3_EXTI28 + USART3 global interrupt and EXTI Line 28 + interrupt + 39 + + + + UART4 + 0x40004C00 + + UART4_EXTI34 + UART4 global and EXTI Line 34 + interrupts + 52 + + + + UART5 + 0x40005000 + + UART5_EXTI35 + UART5 global and EXTI Line 35 + interrupts + 53 + + + + SPI1 + Serial peripheral interface/Inter-IC + sound + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + UDR + Underrun flag + 3 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + MODF + Mode fault + 5 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + TIFRFE + TI frame format error + 8 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO transmission level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 0x00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + I2S2ext + 0x40003400 + + + I2S3ext + 0x40004000 + + + SPI4 + 0x40013C00 + + SPI3 + SPI3 global interrupt + 51 + + + SPI4 + SPI4 Global interrupt + 84 + + + + EXTI + External interrupt/event + controller + EXTI + 0x40010400 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line3 interrupt + 7 + + + EXTI2_TSC + EXTI Line2 and Touch sensing + interrupts + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line5 to Line9 interrupts + 23 + + + I2C1_EV_EXTI23 + I2C1 event interrupt and EXTI Line23 + interrupt + 31 + + + USART1_EXTI25 + USART1 global interrupt and EXTI Line 25 + interrupt + 37 + + + USART2_EXTI26 + USART2 global interrupt and EXTI Line 26 + interrupt + 38 + + + USART3_EXTI28 + USART3 global interrupt and EXTI Line 28 + interrupt + 39 + + + EXTI15_10 + EXTI Line15 to Line10 interrupts + 40 + + + UART4_EXTI34 + UART4 global and EXTI Line 34 + interrupts + 52 + + + UART5_EXTI35 + UART5 global and EXTI Line 35 + interrupts + 53 + + + USB_WKUP_EXTI + USB wakeup from Suspend and EXTI Line + 18 + 76 + + + + IMR1 + IMR1 + Interrupt mask register + 0x0 + 0x20 + read-write + 0x1F800000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + MR23 + Interrupt Mask on line 23 + 23 + 1 + + + MR24 + Interrupt Mask on line 24 + 24 + 1 + + + MR25 + Interrupt Mask on line 25 + 25 + 1 + + + MR26 + Interrupt Mask on line 26 + 26 + 1 + + + MR27 + Interrupt Mask on line 27 + 27 + 1 + + + MR28 + Interrupt Mask on line 28 + 28 + 1 + + + MR29 + Interrupt Mask on line 29 + 29 + 1 + + + MR30 + Interrupt Mask on line 30 + 30 + 1 + + + MR31 + Interrupt Mask on line 31 + 31 + 1 + + + + + EMR1 + EMR1 + Event mask register + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + MR23 + Event Mask on line 23 + 23 + 1 + + + MR24 + Event Mask on line 24 + 24 + 1 + + + MR25 + Event Mask on line 25 + 25 + 1 + + + MR26 + Event Mask on line 26 + 26 + 1 + + + MR27 + Event Mask on line 27 + 27 + 1 + + + MR28 + Event Mask on line 28 + 28 + 1 + + + MR29 + Event Mask on line 29 + 29 + 1 + + + MR30 + Event Mask on line 30 + 30 + 1 + + + MR31 + Event Mask on line 31 + 31 + 1 + + + + + RTSR1 + RTSR1 + Rising Trigger selection + register + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + TR29 + Rising trigger event configuration of + line 29 + 29 + 1 + + + TR30 + Rising trigger event configuration of + line 30 + 30 + 1 + + + TR31 + Rising trigger event configuration of + line 31 + 31 + 1 + + + + + FTSR1 + FTSR1 + Falling Trigger selection + register + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + TR29 + Falling trigger event configuration of + line 29 + 29 + 1 + + + TR30 + Falling trigger event configuration of + line 30. + 30 + 1 + + + TR31 + Falling trigger event configuration of + line 31 + 31 + 1 + + + + + SWIER1 + SWIER1 + Software interrupt event + register + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + SWIER29 + Software Interrupt on line + 29 + 29 + 1 + + + SWIER30 + Software Interrupt on line + 309 + 30 + 1 + + + SWIER31 + Software Interrupt on line + 319 + 31 + 1 + + + + + PR1 + PR1 + Pending register + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + PR29 + Pending bit 29 + 29 + 1 + + + PR30 + Pending bit 30 + 30 + 1 + + + PR31 + Pending bit 31 + 31 + 1 + + + + + IMR2 + IMR2 + Interrupt mask register + 0x18 + 0x20 + read-write + 0xFFFFFFFC + + + MR32 + Interrupt Mask on external/internal line + 32 + 0 + 1 + + + MR33 + Interrupt Mask on external/internal line + 33 + 1 + 1 + + + MR34 + Interrupt Mask on external/internal line + 34 + 2 + 1 + + + MR35 + Interrupt Mask on external/internal line + 35 + 3 + 1 + + + + + EMR2 + EMR2 + Event mask register + 0x1C + 0x20 + read-write + 0x00000000 + + + MR32 + Event mask on external/internal line + 32 + 0 + 1 + + + MR33 + Event mask on external/internal line + 33 + 1 + 1 + + + MR34 + Event mask on external/internal line + 34 + 2 + 1 + + + MR35 + Event mask on external/internal line + 35 + 3 + 1 + + + + + RTSR2 + RTSR2 + Rising Trigger selection + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TR32 + Rising trigger event configuration bit + of line 32 + 0 + 1 + + + TR33 + Rising trigger event configuration bit + of line 33 + 1 + 1 + + + + + FTSR2 + FTSR2 + Falling Trigger selection + register + 0x24 + 0x20 + read-write + 0x00000000 + + + TR32 + Falling trigger event configuration bit + of line 32 + 0 + 1 + + + TR33 + Falling trigger event configuration bit + of line 33 + 1 + 1 + + + + + SWIER2 + SWIER2 + Software interrupt event + register + 0x28 + 0x20 + read-write + 0x00000000 + + + SWIER32 + Software interrupt on line + 32 + 0 + 1 + + + SWIER33 + Software interrupt on line + 33 + 1 + 1 + + + + + PR2 + PR2 + Pending register + 0x2C + 0x20 + read-write + 0x00000000 + + + PR32 + Pending bit on line 32 + 0 + 1 + + + PR33 + Pending bit on line 33 + 1 + 1 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + PVD + PVD through EXTI line detection + interrupt + 1 + + + + CR + CR + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CWUF + Clear wakeup flag + 2 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + + + CSR + CSR + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUF + Wakeup flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + EWUP1 + Enable WKUP1 pin + 8 + 1 + read-write + + + EWUP2 + Enable WKUP2 pin + 9 + 1 + read-write + + + + + + + CAN + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + USB_HP_CAN_TX + USB High Priority/CAN_TX + interrupts + 19 + + + USB_LP_CAN_RX0 + USB Low Priority/CAN_RX0 + interrupts + 20 + + + CAN_RX1 + CAN_RX1 interrupt + 21 + + + CAN_SCE + CAN_SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + error status register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x01230000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + TX mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + TX mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + receive FIFO mailbox data length control and + time stamp register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + receive FIFO mailbox data low + register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + receive FIFO mailbox identifier + register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + receive FIFO mailbox data length control and + time stamp register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + receive FIFO mailbox data low + register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + receive FIFO mailbox data high + register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2 start bank + 8 + 6 + + + FINIT + Filter init mode + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + CAN filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + USB_FS + Universal serial bus full-speed device + interface + USB_FS + 0x40005C00 + + 0x0 + 0x400 + registers + + + USB_WKUP + USB wakeup from Suspend + 42 + + + USB_HP + USB High priority interrupt + 74 + + + USB_LP + USB Low priority interrupt + 75 + + + + USB_EP0R + USB_EP0R + endpoint 0 register + 0x0 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP1R + USB_EP1R + endpoint 1 register + 0x4 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP2R + USB_EP2R + endpoint 2 register + 0x8 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP3R + USB_EP3R + endpoint 3 register + 0xC + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP4R + USB_EP4R + endpoint 4 register + 0x10 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP5R + USB_EP5R + endpoint 5 register + 0x14 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP6R + USB_EP6R + endpoint 6 register + 0x18 + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_EP7R + USB_EP7R + endpoint 7 register + 0x1C + 0x20 + 0x00000000 + + + EA + Endpoint address + 0 + 4 + read-write + + + STAT_TX + Status bits, for transmission + transfers + 4 + 2 + read-write + + + DTOG_TX + Data Toggle, for transmission + transfers + 6 + 1 + read-write + + + CTR_TX + Correct Transfer for + transmission + 7 + 1 + read-write + + + EP_KIND + Endpoint kind + 8 + 1 + read-write + + + EP_TYPE + Endpoint type + 9 + 2 + read-write + + + SETUP + Setup transaction + completed + 11 + 1 + read-only + + + STAT_RX + Status bits, for reception + transfers + 12 + 2 + read-write + + + DTOG_RX + Data Toggle, for reception + transfers + 14 + 1 + read-write + + + CTR_RX + Correct transfer for + reception + 15 + 1 + read-write + + + + + USB_CNTR + USB_CNTR + control register + 0x40 + 0x20 + read-write + 0x00000003 + + + FRES + Force USB Reset + 0 + 1 + + + PDWN + Power down + 1 + 1 + + + LPMODE + Low-power mode + 2 + 1 + + + FSUSP + Force suspend + 3 + 1 + + + RESUME + Resume request + 4 + 1 + + + ESOFM + Expected start of frame interrupt + mask + 8 + 1 + + + SOFM + Start of frame interrupt + mask + 9 + 1 + + + RESETM + USB reset interrupt mask + 10 + 1 + + + SUSPM + Suspend mode interrupt + mask + 11 + 1 + + + WKUPM + Wakeup interrupt mask + 12 + 1 + + + ERRM + Error interrupt mask + 13 + 1 + + + PMAOVRM + Packet memory area over / underrun + interrupt mask + 14 + 1 + + + CTRM + Correct transfer interrupt + mask + 15 + 1 + + + + + ISTR + ISTR + interrupt status register + 0x44 + 0x20 + 0x00000000 + + + EP_ID + Endpoint Identifier + 0 + 4 + read-only + + + DIR + Direction of transaction + 4 + 1 + read-only + + + ESOF + Expected start frame + 8 + 1 + read-write + + + SOF + start of frame + 9 + 1 + read-write + + + RESET + reset request + 10 + 1 + read-write + + + SUSP + Suspend mode request + 11 + 1 + read-write + + + WKUP + Wakeup + 12 + 1 + read-write + + + ERR + Error + 13 + 1 + read-write + + + PMAOVR + Packet memory area over / + underrun + 14 + 1 + read-write + + + CTR + Correct transfer + 15 + 1 + read-only + + + + + FNR + FNR + frame number register + 0x48 + 0x20 + read-only + 0x0000 + + + FN + Frame number + 0 + 11 + + + LSOF + Lost SOF + 11 + 2 + + + LCK + Locked + 13 + 1 + + + RXDM + Receive data - line status + 14 + 1 + + + RXDP + Receive data + line status + 15 + 1 + + + + + DADDR + DADDR + device address + 0x4C + 0x20 + read-write + 0x0000 + + + ADD + Device address + 0 + 1 + + + ADD1 + Device address + 1 + 1 + + + ADD2 + Device address + 2 + 1 + + + ADD3 + Device address + 3 + 1 + + + ADD4 + Device address + 4 + 1 + + + ADD5 + Device address + 5 + 1 + + + ADD6 + Device address + 6 + 1 + + + EF + Enable function + 7 + 1 + + + + + BTABLE + BTABLE + Buffer table address + 0x50 + 0x20 + read-write + 0x0000 + + + BTABLE + Buffer table + 3 + 13 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EV_EXTI23 + I2C1 event interrupt and EXTI Line23 + interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + 0x00000000 + + + PE + Peripheral enable + 0 + 1 + read-write + + + TXIE + TX Interrupt enable + 1 + 1 + read-write + + + RXIE + RX Interrupt enable + 2 + 1 + read-write + + + ADDRIE + Address match interrupt enable (slave + only) + 3 + 1 + read-write + + + NACKIE + Not acknowledge received interrupt + enable + 4 + 1 + read-write + + + STOPIE + STOP detection Interrupt + enable + 5 + 1 + read-write + + + TCIE + Transfer Complete interrupt + enable + 6 + 1 + read-write + + + ERRIE + Error interrupts enable + 7 + 1 + read-write + + + DNF + Digital noise filter + 8 + 4 + read-write + + + ANFOFF + Analog noise filter OFF + 12 + 1 + read-write + + + SWRST + Software reset + 13 + 1 + write-only + + + TXDMAEN + DMA transmission requests + enable + 14 + 1 + read-write + + + RXDMAEN + DMA reception requests + enable + 15 + 1 + read-write + + + SBC + Slave byte control + 16 + 1 + read-write + + + NOSTRETCH + Clock stretching disable + 17 + 1 + read-write + + + WUPEN + Wakeup from STOP enable + 18 + 1 + read-write + + + GCEN + General call enable + 19 + 1 + read-write + + + SMBHEN + SMBus Host address enable + 20 + 1 + read-write + + + SMBDEN + SMBus Device Default address + enable + 21 + 1 + read-write + + + ALERTEN + SMBUS alert enable + 22 + 1 + read-write + + + PECEN + PEC enable + 23 + 1 + read-write + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECBYTE + Packet error checking byte + 26 + 1 + + + AUTOEND + Automatic end mode (master + mode) + 25 + 1 + + + RELOAD + NBYTES reload mode + 24 + 1 + + + NBYTES + Number of bytes + 16 + 8 + + + NACK + NACK generation (slave + mode) + 15 + 1 + + + STOP + Stop generation (master + mode) + 14 + 1 + + + START + Start generation + 13 + 1 + + + HEAD10R + 10-bit address header only read + direction (master receiver mode) + 12 + 1 + + + ADD10 + 10-bit addressing mode (master + mode) + 11 + 1 + + + RD_WRN + Transfer direction (master + mode) + 10 + 1 + + + SADD8 + Slave address bit 9:8 (master + mode) + 8 + 2 + + + SADD1 + Slave address bit 7:1 (master + mode) + 1 + 7 + + + SADD0 + Slave address bit 0 (master + mode) + 0 + 1 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + OA1_0 + Interface address + 0 + 1 + + + OA1_1 + Interface address + 1 + 7 + + + OA1_8 + Interface address + 8 + 2 + + + OA1MODE + Own Address 1 10-bit mode + 10 + 1 + + + OA1EN + Own Address 1 enable + 15 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + OA2 + Interface address + 1 + 7 + + + OA2MSK + Own Address 2 masks + 8 + 3 + + + OA2EN + Own Address 2 enable + 15 + 1 + + + + + TIMINGR + TIMINGR + Timing register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low period (master + mode) + 0 + 8 + + + SCLH + SCL high period (master + mode) + 8 + 8 + + + SDADEL + Data hold time + 16 + 4 + + + SCLDEL + Data setup time + 20 + 4 + + + PRESC + Timing prescaler + 28 + 4 + + + + + TIMEOUTR + TIMEOUTR + Status register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + TIMEOUTA + Bus timeout A + 0 + 12 + + + TIDLE + Idle clock timeout + detection + 12 + 1 + + + TIMOUTEN + Clock timeout enable + 15 + 1 + + + TIMEOUTB + Bus timeout B + 16 + 12 + + + TEXTEN + Extended clock timeout + enable + 31 + 1 + + + + + ISR + ISR + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDCODE + Address match code (Slave + mode) + 17 + 7 + read-only + + + DIR + Transfer direction (Slave + mode) + 16 + 1 + read-only + + + BUSY + Bus busy + 15 + 1 + read-only + + + ALERT + SMBus alert + 13 + 1 + read-only + + + TIMEOUT + Timeout or t_low detection + flag + 12 + 1 + read-only + + + PECERR + PEC Error in reception + 11 + 1 + read-only + + + OVR + Overrun/Underrun (slave + mode) + 10 + 1 + read-only + + + ARLO + Arbitration lost + 9 + 1 + read-only + + + BERR + Bus error + 8 + 1 + read-only + + + TCR + Transfer Complete Reload + 7 + 1 + read-only + + + TC + Transfer Complete (master + mode) + 6 + 1 + read-only + + + STOPF + Stop detection flag + 5 + 1 + read-only + + + NACKF + Not acknowledge received + flag + 4 + 1 + read-only + + + ADDR + Address matched (slave + mode) + 3 + 1 + read-only + + + RXNE + Receive data register not empty + (receivers) + 2 + 1 + read-only + + + TXIS + Transmit interrupt status + (transmitters) + 1 + 1 + read-write + + + TXE + Transmit data register empty + (transmitters) + 0 + 1 + read-write + + + + + ICR + ICR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTCF + Alert flag clear + 13 + 1 + + + TIMOUTCF + Timeout detection flag + clear + 12 + 1 + + + PECCF + PEC Error flag clear + 11 + 1 + + + OVRCF + Overrun/Underrun flag + clear + 10 + 1 + + + ARLOCF + Arbitration lost flag + clear + 9 + 1 + + + BERRCF + Bus error flag clear + 8 + 1 + + + STOPCF + Stop detection flag clear + 5 + 1 + + + NACKCF + Not Acknowledge flag clear + 4 + 1 + + + ADDRCF + Address Matched flag clear + 3 + 1 + + + + + PECR + PECR + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PEC + Packet error checking + register + 0 + 8 + + + + + RXDR + RXDR + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + RXDATA + 8-bit receive data + 0 + 8 + + + + + TXDR + TXDR + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + TXDATA + 8-bit transmit data + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + I2C2_EV_EXTI24 + I2C2 event interrupt & EXTI Line24 + interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2C3 + 0x40007800 + + I2C2_EV_EXTI24 + I2C2 event interrupt & EXTI Line24 + interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + I2C3_EV + I2C3 Event interrupt + 72 + + + I2C3_ER + I2C3 Error interrupt + 73 + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + WVU + Watchdog counter window value + update + 2 + 1 + + + + + WINR + WINR + Window register + 0x10 + 0x20 + read-write + 0x00000FFF + + + WIN + Watchdog counter window + value + 0 + 12 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x0000007F + + + T + 7-bit counter + 0 + 7 + + + WDGA + Activation bit + 7 + 1 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x0000007F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB + Timer base + 7 + 2 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00000000 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTCAlarm + RTC alarm interrupt + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + BYPSHAD + Bypass the shadow + registers + 5 + 1 + + + FMT + Hour format + 6 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + BKP + Backup + 18 + 1 + + + COSEL + Calibration output + selection + 19 + 1 + + + POL + Output polarity + 20 + 1 + + + OSEL + Output selection + 21 + 2 + + + COE + Calibration output enable + 23 + 1 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + RTC_TAMP2 detection flag + 14 + 1 + read-write + + + TAMP3F + RTC_TAMP3 detection flag + 15 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAFCR + TAFCR + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP3E + Tamper 3 detection enable + 5 + 1 + + + TAMP3TRG + Active level for tamper 3 + 6 + 1 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + PC13VALUE + PC13 value + 18 + 1 + + + PC13MODE + PC13 mode + 19 + 1 + + + PC14VALUE + PC14 value + 20 + 1 + + + PC14MODE + PC 14 mode + 21 + 1 + + + PC15VALUE + PC15 value + 22 + 1 + + + PC15MODE + PC15 mode + 23 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP20R + BKP20R + backup register + 0xA0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP21R + BKP21R + backup register + 0xA4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP22R + BKP22R + backup register + 0xA8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP23R + BKP23R + backup register + 0xAC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP24R + BKP24R + backup register + 0xB0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP25R + BKP25R + backup register + 0xB4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP26R + BKP26R + backup register + 0xB8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP27R + BKP27R + backup register + 0xBC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP28R + BKP28R + backup register + 0xC0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP29R + BKP29R + backup register + 0xC4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP30R + BKP30R + backup register + 0xC8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP31R + BKP31R + backup register + 0xCC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + TIM6 + Basic timers + TIMs + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DACUNDER + TIM6 global and DAC12 underrun + interrupts + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + Low counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + TIM6_DACUNDER + TIM6 global and DAC12 underrun + interrupts + 54 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + DBGMCU + Debug support + DBGMCU + 0xE0042000 + + 0x0 + 0x400 + registers + + + + IDCODE + IDCODE + MCU Device ID Code Register + 0x0 + 0x20 + read-only + 0x0 + + + DEV_ID + Device Identifier + 0 + 12 + + + REV_ID + Revision Identifier + 16 + 16 + + + + + CR + CR + Debug MCU Configuration + Register + 0x4 + 0x20 + read-write + 0x0 + + + DBG_SLEEP + Debug Sleep mode + 0 + 1 + + + DBG_STOP + Debug Stop Mode + 1 + 1 + + + DBG_STANDBY + Debug Standby Mode + 2 + 1 + + + TRACE_IOEN + Trace pin assignment + control + 5 + 1 + + + TRACE_MODE + Trace pin assignment + control + 6 + 2 + + + + + APB1FZ + APB1FZ + APB Low Freeze Register + 0x8 + 0x20 + read-write + 0x0 + + + DBG_TIM2_STOP + Debug Timer 2 stopped when Core is + halted + 0 + 1 + + + DBG_TIM3_STOP + Debug Timer 3 stopped when Core is + halted + 1 + 1 + + + DBG_TIM4_STOP + Debug Timer 4 stopped when Core is + halted + 2 + 1 + + + DBG_TIM5_STOP + Debug Timer 5 stopped when Core is + halted + 3 + 1 + + + DBG_TIM6_STOP + Debug Timer 6 stopped when Core is + halted + 4 + 1 + + + DBG_TIM7_STOP + Debug Timer 7 stopped when Core is + halted + 5 + 1 + + + DBG_TIM12_STOP + Debug Timer 12 stopped when Core is + halted + 6 + 1 + + + DBG_TIM13_STOP + Debug Timer 13 stopped when Core is + halted + 7 + 1 + + + DBG_TIMER14_STOP + Debug Timer 14 stopped when Core is + halted + 8 + 1 + + + DBG_TIM18_STOP + Debug Timer 18 stopped when Core is + halted + 9 + 1 + + + DBG_RTC_STOP + Debug RTC stopped when Core is + halted + 10 + 1 + + + DBG_WWDG_STOP + Debug Window Wachdog stopped when Core + is halted + 11 + 1 + + + DBG_IWDG_STOP + Debug Independent Wachdog stopped when + Core is halted + 12 + 1 + + + I2C1_SMBUS_TIMEOUT + SMBUS timeout mode stopped when Core is + halted + 21 + 1 + + + I2C2_SMBUS_TIMEOUT + SMBUS timeout mode stopped when Core is + halted + 22 + 1 + + + DBG_CAN_STOP + Debug CAN stopped when core is + halted + 25 + 1 + + + + + APB2FZ + APB2FZ + APB High Freeze Register + 0xC + 0x20 + read-write + 0x0 + + + DBG_TIM15_STOP + Debug Timer 15 stopped when Core is + halted + 2 + 1 + + + DBG_TIM16_STOP + Debug Timer 16 stopped when Core is + halted + 3 + 1 + + + DBG_TIM17_STO + Debug Timer 17 stopped when Core is + halted + 4 + 1 + + + DBG_TIM19_STOP + Debug Timer 19 stopped when Core is + halted + 5 + 1 + + + + + + + TIM1 + Advanced timer + TIMs + 0x40012C00 + + 0x0 + 0x400 + registers + + + TIM1_CC + TIM1 capture compare interrupt + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + DIR + Direction + 4 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + MMS + Master mode selection + 4 + 3 + + + TI1S + TI1 selection + 7 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS5 + Output Idle state 5 + 16 + 1 + + + OIS6 + Output Idle state 6 + 18 + 1 + + + MMS2 + Master mode selection 2 + 20 + 4 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + OCCS + OCREF clear selection + 3 + 1 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS3 + Slave mode selection bit 3 + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + B2IF + Break 2 interrupt flag + 8 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + C5IF + Capture/Compare 5 interrupt + flag + 16 + 1 + + + C6IF + Capture/Compare 6 interrupt + flag + 17 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + TG + Trigger generation + 6 + 1 + + + BG + Break generation + 7 + 1 + + + B2G + Break 2 generation + 8 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1M_3 + Output Compare 1 mode bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + OC3M_3 + Output Compare 3 mode bit + 3 + 16 + 1 + + + OC4M_3 + Output Compare 4 mode bit + 3 + 24 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC5E + Capture/Compare 5 output + enable + 16 + 1 + + + CC5P + Capture/Compare 5 output + Polarity + 17 + 1 + + + CC6E + Capture/Compare 6 output + enable + 20 + 1 + + + CC6P + Capture/Compare 6 output + Polarity + 21 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare 3 value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare 3 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x00000000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + BK2F + Break 2 filter + 20 + 4 + + + BK2E + Break 2 enable + 24 + 1 + + + BK2P + Break 2 polarity + 25 + 1 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x00000000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x00000000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x00000000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M_3 + Outout Compare 5 mode bit + 3 + 16 + 1 + + + OC6M_3 + Outout Compare 6 mode bit + 3 + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x00000000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CCR6 + CCR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x00000000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + OR + OR + option registers + 0x60 + 0x20 + read-write + 0x00000000 + + + TIM1_ETR_ADC1_RMP + TIM1_ETR_ADC1 remapping + capability + 0 + 2 + + + TIM1_ETR_ADC4_RMP + TIM1_ETR_ADC4 remapping + capability + 2 + 2 + + + + + + + TIM20 + 0x40015000 + + TIM1_CC + TIM1 capture compare interrupt + 27 + + + TIM20_BRK + TIM20 Break interrupt + 77 + + + TIM20_UP + TIM20 Upgrade interrupt + 78 + + + TIM20_TRG_COM + TIM20 Trigger and Commutation + interrupt + 79 + + + TIM20_CC + TIM20 Capture Compare interrupt + 80 + + + + TIM8 + Advanced-timers + TIMs + 0x40013400 + + 0x0 + 0x400 + registers + + + TIM8_BRK + TIM8 break interrupt + 43 + + + TIM8_UP + TIM8 update interrupt + 44 + + + TIM8_TRG_COM + TIM8 Trigger and commutation + interrupts + 45 + + + TIM8_CC + TIM8 capture compare interrupt + 46 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + DIR + Direction + 4 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + MMS + Master mode selection + 4 + 3 + + + TI1S + TI1 selection + 7 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS5 + Output Idle state 5 + 16 + 1 + + + OIS6 + Output Idle state 6 + 18 + 1 + + + MMS2 + Master mode selection 2 + 20 + 4 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + OCCS + OCREF clear selection + 3 + 1 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS3 + Slave mode selection bit 3 + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + B2IF + Break 2 interrupt flag + 8 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + C5IF + Capture/Compare 5 interrupt + flag + 16 + 1 + + + C6IF + Capture/Compare 6 interrupt + flag + 17 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + TG + Trigger generation + 6 + 1 + + + BG + Break generation + 7 + 1 + + + B2G + Break 2 generation + 8 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1M_3 + Output Compare 1 mode bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + OC3M_3 + Output Compare 3 mode bit + 3 + 16 + 1 + + + OC4M_3 + Output Compare 4 mode bit + 3 + 24 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC5E + Capture/Compare 5 output + enable + 16 + 1 + + + CC5P + Capture/Compare 5 output + Polarity + 17 + 1 + + + CC6E + Capture/Compare 6 output + enable + 20 + 1 + + + CC6P + Capture/Compare 6 output + Polarity + 21 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare 3 value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare 3 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x00000000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + BK2F + Break 2 filter + 20 + 4 + + + BK2E + Break 2 enable + 24 + 1 + + + BK2P + Break 2 polarity + 25 + 1 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x00000000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x00000000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x00000000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M_3 + Outout Compare 5 mode bit + 3 + 16 + 1 + + + OC6M_3 + Outout Compare 6 mode bit + 3 + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x00000000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CCR6 + CCR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x00000000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + OR + OR + option registers + 0x60 + 0x20 + read-write + 0x00000000 + + + TIM8_ETR_ADC2_RMP + TIM8_ETR_ADC2 remapping + capability + 0 + 2 + + + TIM8_ETR_ADC3_RMP + TIM8_ETR_ADC3 remapping + capability + 2 + 2 + + + + + + + ADC1 + Analog-to-Digital Converter + ADC + 0x50000000 + + 0x0 + 0x100 + registers + + + ADC1_2 + ADC1 and ADC2 global interrupt + 18 + + + + ISR + ISR + interrupt and status register + 0x0 + 0x20 + read-write + 0x00000000 + + + JQOVF + JQOVF + 10 + 1 + + + AWD3 + AWD3 + 9 + 1 + + + AWD2 + AWD2 + 8 + 1 + + + AWD1 + AWD1 + 7 + 1 + + + JEOS + JEOS + 6 + 1 + + + JEOC + JEOC + 5 + 1 + + + OVR + OVR + 4 + 1 + + + EOS + EOS + 3 + 1 + + + EOC + EOC + 2 + 1 + + + EOSMP + EOSMP + 1 + 1 + + + ADRDY + ADRDY + 0 + 1 + + + + + IER + IER + interrupt enable register + 0x4 + 0x20 + read-write + 0x00000000 + + + JQOVFIE + JQOVFIE + 10 + 1 + + + AWD3IE + AWD3IE + 9 + 1 + + + AWD2IE + AWD2IE + 8 + 1 + + + AWD1IE + AWD1IE + 7 + 1 + + + JEOSIE + JEOSIE + 6 + 1 + + + JEOCIE + JEOCIE + 5 + 1 + + + OVRIE + OVRIE + 4 + 1 + + + EOSIE + EOSIE + 3 + 1 + + + EOCIE + EOCIE + 2 + 1 + + + EOSMPIE + EOSMPIE + 1 + 1 + + + ADRDYIE + ADRDYIE + 0 + 1 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + ADCAL + ADCAL + 31 + 1 + + + ADCALDIF + ADCALDIF + 30 + 1 + + + DEEPPWD + DEEPPWD + 29 + 1 + + + ADVREGEN + ADVREGEN + 28 + 1 + + + JADSTP + JADSTP + 5 + 1 + + + ADSTP + ADSTP + 4 + 1 + + + JADSTART + JADSTART + 3 + 1 + + + ADSTART + ADSTART + 2 + 1 + + + ADDIS + ADDIS + 1 + 1 + + + ADEN + ADEN + 0 + 1 + + + + + CFGR + CFGR + configuration register + 0xC + 0x20 + read-write + 0x00000000 + + + AWDCH1CH + AWDCH1CH + 26 + 5 + + + JAUTO + JAUTO + 25 + 1 + + + JAWD1EN + JAWD1EN + 24 + 1 + + + AWD1EN + AWD1EN + 23 + 1 + + + AWD1SGL + AWD1SGL + 22 + 1 + + + JQM + JQM + 21 + 1 + + + JDISCEN + JDISCEN + 20 + 1 + + + DISCNUM + DISCNUM + 17 + 3 + + + DISCEN + DISCEN + 16 + 1 + + + AUTOFF + AUTOFF + 15 + 1 + + + AUTDLY + AUTDLY + 14 + 1 + + + CONT + CONT + 13 + 1 + + + OVRMOD + OVRMOD + 12 + 1 + + + EXTEN + EXTEN + 10 + 2 + + + EXTSEL + EXTSEL + 6 + 4 + + + ALIGN + ALIGN + 5 + 1 + + + RES + RES + 3 + 2 + + + DMACFG + DMACFG + 1 + 1 + + + DMAEN + DMAEN + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + SMP9 + SMP9 + 27 + 3 + + + SMP8 + SMP8 + 24 + 3 + + + SMP7 + SMP7 + 21 + 3 + + + SMP6 + SMP6 + 18 + 3 + + + SMP5 + SMP5 + 15 + 3 + + + SMP4 + SMP4 + 12 + 3 + + + SMP3 + SMP3 + 9 + 3 + + + SMP2 + SMP2 + 6 + 3 + + + SMP1 + SMP1 + 3 + 3 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x18 + 0x20 + read-write + 0x00000000 + + + SMP18 + SMP18 + 24 + 3 + + + SMP17 + SMP17 + 21 + 3 + + + SMP16 + SMP16 + 18 + 3 + + + SMP15 + SMP15 + 15 + 3 + + + SMP14 + SMP14 + 12 + 3 + + + SMP13 + SMP13 + 9 + 3 + + + SMP12 + SMP12 + 6 + 3 + + + SMP11 + SMP11 + 3 + 3 + + + SMP10 + SMP10 + 0 + 3 + + + + + TR1 + TR1 + watchdog threshold register 1 + 0x20 + 0x20 + read-write + 0x0FFF0000 + + + HT1 + HT1 + 16 + 12 + + + LT1 + LT1 + 0 + 12 + + + + + TR2 + TR2 + watchdog threshold register + 0x24 + 0x20 + read-write + 0x0FFF0000 + + + HT2 + HT2 + 16 + 8 + + + LT2 + LT2 + 0 + 8 + + + + + TR3 + TR3 + watchdog threshold register 3 + 0x28 + 0x20 + read-write + 0x0FFF0000 + + + HT3 + HT3 + 16 + 8 + + + LT3 + LT3 + 0 + 8 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ4 + SQ4 + 24 + 5 + + + SQ3 + SQ3 + 18 + 5 + + + SQ2 + SQ2 + 12 + 5 + + + SQ1 + SQ1 + 6 + 5 + + + L3 + L3 + 0 + 4 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ9 + SQ9 + 24 + 5 + + + SQ8 + SQ8 + 18 + 5 + + + SQ7 + SQ7 + 12 + 5 + + + SQ6 + SQ6 + 6 + 5 + + + SQ5 + SQ5 + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x38 + 0x20 + read-write + 0x00000000 + + + SQ14 + SQ14 + 24 + 5 + + + SQ13 + SQ13 + 18 + 5 + + + SQ12 + SQ12 + 12 + 5 + + + SQ11 + SQ11 + 6 + 5 + + + SQ10 + SQ10 + 0 + 5 + + + + + SQR4 + SQR4 + regular sequence register 4 + 0x3C + 0x20 + read-write + 0x00000000 + + + SQ16 + SQ16 + 6 + 5 + + + SQ15 + SQ15 + 0 + 5 + + + + + DR + DR + regular Data Register + 0x40 + 0x20 + read-only + 0x00000000 + + + regularDATA + regularDATA + 0 + 16 + + + + + JSQR + JSQR + injected sequence register + 0x4C + 0x20 + read-write + 0x00000000 + + + JSQ4 + JSQ4 + 26 + 5 + + + JSQ3 + JSQ3 + 20 + 5 + + + JSQ2 + JSQ2 + 14 + 5 + + + JSQ1 + JSQ1 + 8 + 5 + + + JEXTEN + JEXTEN + 6 + 2 + + + JEXTSEL + JEXTSEL + 2 + 4 + + + JL + JL + 0 + 2 + + + + + OFR1 + OFR1 + offset register 1 + 0x60 + 0x20 + read-write + 0x00000000 + + + OFFSET1_EN + OFFSET1_EN + 31 + 1 + + + OFFSET1_CH + OFFSET1_CH + 26 + 5 + + + OFFSET1 + OFFSET1 + 0 + 12 + + + + + OFR2 + OFR2 + offset register 2 + 0x64 + 0x20 + read-write + 0x00000000 + + + OFFSET2_EN + OFFSET2_EN + 31 + 1 + + + OFFSET2_CH + OFFSET2_CH + 26 + 5 + + + OFFSET2 + OFFSET2 + 0 + 12 + + + + + OFR3 + OFR3 + offset register 3 + 0x68 + 0x20 + read-write + 0x00000000 + + + OFFSET3_EN + OFFSET3_EN + 31 + 1 + + + OFFSET3_CH + OFFSET3_CH + 26 + 5 + + + OFFSET3 + OFFSET3 + 0 + 12 + + + + + OFR4 + OFR4 + offset register 4 + 0x6C + 0x20 + read-write + 0x00000000 + + + OFFSET4_EN + OFFSET4_EN + 31 + 1 + + + OFFSET4_CH + OFFSET4_CH + 26 + 5 + + + OFFSET4 + OFFSET4 + 0 + 12 + + + + + JDR1 + JDR1 + injected data register 1 + 0x80 + 0x20 + read-only + 0x00000000 + + + JDATA1 + JDATA1 + 0 + 16 + + + + + JDR2 + JDR2 + injected data register 2 + 0x84 + 0x20 + read-only + 0x00000000 + + + JDATA2 + JDATA2 + 0 + 16 + + + + + JDR3 + JDR3 + injected data register 3 + 0x88 + 0x20 + read-only + 0x00000000 + + + JDATA3 + JDATA3 + 0 + 16 + + + + + JDR4 + JDR4 + injected data register 4 + 0x8C + 0x20 + read-only + 0x00000000 + + + JDATA4 + JDATA4 + 0 + 16 + + + + + AWD2CR + AWD2CR + Analog Watchdog 2 Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000000 + + + AWD2CH + AWD2CH + 1 + 18 + + + + + AWD3CR + AWD3CR + Analog Watchdog 3 Configuration + Register + 0xA4 + 0x20 + read-write + 0x00000000 + + + AWD3CH + AWD3CH + 1 + 18 + + + + + DIFSEL + DIFSEL + Differential Mode Selection Register + 2 + 0xB0 + 0x20 + 0x00000000 + + + DIFSEL_1_15 + Differential mode for channels 15 to + 1 + 1 + 15 + read-write + + + DIFSEL_16_18 + Differential mode for channels 18 to + 16 + 16 + 3 + read-only + + + + + CALFACT + CALFACT + Calibration Factors + 0xB4 + 0x20 + read-write + 0x00000000 + + + CALFACT_D + CALFACT_D + 16 + 7 + + + CALFACT_S + CALFACT_S + 0 + 7 + + + + + + + ADC2 + 0x50000100 + + ADC1_2 + ADC1 and ADC2 global interrupt + 18 + + + + ADC3 + 0x50000400 + + ADC3 + ADC3 global interrupt + 47 + + + + ADC4 + 0x50000500 + + ADC4 + ADC4 global interrupt + 61 + + + + ADC1_2 + Analog-to-Digital Converter + ADC + 0x50000300 + + 0x0 + 0x11 + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + ADDRDY_MST + ADDRDY_MST + 0 + 1 + + + EOSMP_MST + EOSMP_MST + 1 + 1 + + + EOC_MST + EOC_MST + 2 + 1 + + + EOS_MST + EOS_MST + 3 + 1 + + + OVR_MST + OVR_MST + 4 + 1 + + + JEOC_MST + JEOC_MST + 5 + 1 + + + JEOS_MST + JEOS_MST + 6 + 1 + + + AWD1_MST + AWD1_MST + 7 + 1 + + + AWD2_MST + AWD2_MST + 8 + 1 + + + AWD3_MST + AWD3_MST + 9 + 1 + + + JQOVF_MST + JQOVF_MST + 10 + 1 + + + ADRDY_SLV + ADRDY_SLV + 16 + 1 + + + EOSMP_SLV + EOSMP_SLV + 17 + 1 + + + EOC_SLV + End of regular conversion of the slave + ADC + 18 + 1 + + + EOS_SLV + End of regular sequence flag of the + slave ADC + 19 + 1 + + + OVR_SLV + Overrun flag of the slave + ADC + 20 + 1 + + + JEOC_SLV + End of injected conversion flag of the + slave ADC + 21 + 1 + + + JEOS_SLV + End of injected sequence flag of the + slave ADC + 22 + 1 + + + AWD1_SLV + Analog watchdog 1 flag of the slave + ADC + 23 + 1 + + + AWD2_SLV + Analog watchdog 2 flag of the slave + ADC + 24 + 1 + + + AWD3_SLV + Analog watchdog 3 flag of the slave + ADC + 25 + 1 + + + JQOVF_SLV + Injected Context Queue Overflow flag of + the slave ADC + 26 + 1 + + + + + CCR + CCR + ADC common control register + 0x8 + 0x20 + read-write + 0x00000000 + + + MULT + Multi ADC mode selection + 0 + 5 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + DMACFG + DMA configuration (for multi-ADC + mode) + 13 + 1 + + + MDMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + CKMODE + ADC clock mode + 16 + 2 + + + VREFEN + VREFINT enable + 22 + 1 + + + TSEN + Temperature sensor enable + 23 + 1 + + + VBATEN + VBAT enable + 24 + 1 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0xC + 0x20 + read-only + 0x00000000 + + + RDATA_SLV + Regular data of the slave + ADC + 16 + 16 + + + RDATA_MST + Regular data of the master + ADC + 0 + 16 + + + + + + + ADC3_4 + 0x50000700 + + + SYSCFG_COMP_OPAMP + System configuration controller _Comparator and + Operational amplifier + SYSCFG_COMP_OPAMP + 0x40010000 + + 0x0 + 0x400 + registers + + + COMP123 + COMP1 & COMP2 & COMP3 interrupts + combined with EXTI Lines 21, 22 and 29 + interrupts + 64 + + + COMP456 + COMP4 & COMP5 & COMP6 interrupts + combined with EXTI Lines 30, 31 and 32 + interrupts + 65 + + + COMP7 + COMP7 interrupt combined with EXTI Line 33 + interrupt + 66 + + + + SYSCFG_CFGR1 + SYSCFG_CFGR1 + configuration register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + Memory mapping selection + bits + 0 + 2 + + + USB_IT_RMP + USB interrupt remap + 5 + 1 + + + TIM1_ITR_RMP + Timer 1 ITR3 selection + 6 + 1 + + + DAC_TRIG_RMP + DAC trigger remap (when TSEL = + 001) + 7 + 1 + + + ADC24_DMA_RMP + ADC24 DMA remapping bit + 8 + 1 + + + TIM16_DMA_RMP + TIM16 DMA request remapping + bit + 11 + 1 + + + TIM17_DMA_RMP + TIM17 DMA request remapping + bit + 12 + 1 + + + TIM6_DAC1_DMA_RMP + TIM6 and DAC1 DMA request remapping + bit + 13 + 1 + + + TIM7_DAC2_DMA_RMP + TIM7 and DAC2 DMA request remapping + bit + 14 + 1 + + + I2C_PB6_FM + Fast Mode Plus (FM+) driving capability + activation bits. + 16 + 1 + + + I2C_PB7_FM + Fast Mode Plus (FM+) driving capability + activation bits. + 17 + 1 + + + I2C_PB8_FM + Fast Mode Plus (FM+) driving capability + activation bits. + 18 + 1 + + + I2C_PB9_FM + Fast Mode Plus (FM+) driving capability + activation bits. + 19 + 1 + + + I2C1_FM + I2C1 Fast Mode Plus + 20 + 1 + + + I2C2_FM + I2C2 Fast Mode Plus + 21 + 1 + + + ENCODER_MODE + Encoder mode + 22 + 2 + + + FPU_IT + Interrupt enable bits from + FPU + 26 + 6 + + + + + SYSCFG_EXTICR1 + SYSCFG_EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI 3 configuration bits + 12 + 4 + + + EXTI2 + EXTI 2 configuration bits + 8 + 4 + + + EXTI1 + EXTI 1 configuration bits + 4 + 4 + + + EXTI0 + EXTI 0 configuration bits + 0 + 4 + + + + + SYSCFG_EXTICR2 + SYSCFG_EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI 7 configuration bits + 12 + 4 + + + EXTI6 + EXTI 6 configuration bits + 8 + 4 + + + EXTI5 + EXTI 5 configuration bits + 4 + 4 + + + EXTI4 + EXTI 4 configuration bits + 0 + 4 + + + + + SYSCFG_EXTICR3 + SYSCFG_EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI 11 configuration bits + 12 + 4 + + + EXTI10 + EXTI 10 configuration bits + 8 + 4 + + + EXTI9 + EXTI 9 configuration bits + 4 + 4 + + + EXTI8 + EXTI 8 configuration bits + 0 + 4 + + + + + SYSCFG_EXTICR4 + SYSCFG_EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI 15 configuration bits + 12 + 4 + + + EXTI14 + EXTI 14 configuration bits + 8 + 4 + + + EXTI13 + EXTI 13 configuration bits + 4 + 4 + + + EXTI12 + EXTI 12 configuration bits + 0 + 4 + + + + + SYSCFG_CFGR2 + SYSCFG_CFGR2 + configuration register 2 + 0x18 + 0x20 + read-write + 0x0000 + + + LOCUP_LOCK + Cortex-M0 LOCKUP bit enable + bit + 0 + 1 + + + SRAM_PARITY_LOCK + SRAM parity lock bit + 1 + 1 + + + PVD_LOCK + PVD lock enable bit + 2 + 1 + + + BYP_ADD_PAR + Bypass address bit 29 in parity + calculation + 4 + 1 + + + SRAM_PEF + SRAM parity flag + 8 + 1 + + + + + SYSCFG_RCR + SYSCFG_RCR + CCM SRAM protection register + 0x4 + 0x20 + read-write + 0x0000 + + + PAGE0_WP + CCM SRAM page write protection + bit + 0 + 1 + + + PAGE1_WP + CCM SRAM page write protection + bit + 1 + 1 + + + PAGE2_WP + CCM SRAM page write protection + bit + 2 + 1 + + + PAGE3_WP + CCM SRAM page write protection + bit + 3 + 1 + + + PAGE4_WP + CCM SRAM page write protection + bit + 4 + 1 + + + PAGE5_WP + CCM SRAM page write protection + bit + 5 + 1 + + + PAGE6_WP + CCM SRAM page write protection + bit + 6 + 1 + + + PAGE7_WP + CCM SRAM page write protection + bit + 7 + 1 + + + + + COMP1_CSR + COMP1_CSR + control and status register + 0x1C + 0x20 + 0x0000 + + + COMP1EN + Comparator 1 enable + 0 + 1 + read-write + + + COMP1_INP_DAC + COMP1_INP_DAC + 1 + 1 + read-write + + + COMP1MODE + Comparator 1 mode + 2 + 2 + read-write + + + COMP1INSEL + Comparator 1 inverting input + selection + 4 + 3 + read-write + + + COMP1_OUT_SEL + Comparator 1 output + selection + 10 + 4 + read-write + + + COMP1POL + Comparator 1 output + polarity + 15 + 1 + read-write + + + COMP1HYST + Comparator 1 hysteresis + 16 + 2 + read-write + + + COMP1_BLANKING + Comparator 1 blanking + source + 18 + 3 + read-write + + + COMP1OUT + Comparator 1 output + 30 + 1 + read-only + + + COMP1LOCK + Comparator 1 lock + 31 + 1 + read-write + + + + + COMP2_CSR + COMP2_CSR + control and status register + 0x20 + 0x20 + read-write + 0x0000 + + + COMP2EN + Comparator 2 enable + 0 + 1 + + + COMP2MODE + Comparator 2 mode + 2 + 2 + + + COMP2INSEL + Comparator 2 inverting input + selection + 4 + 3 + + + COMP2INPSEL + Comparator 2 non inverted input + selection + 7 + 1 + + + COMP2INMSEL + Comparator 1inverting input + selection + 9 + 1 + + + COMP2_OUT_SEL + Comparator 2 output + selection + 10 + 4 + + + COMP2POL + Comparator 2 output + polarity + 15 + 1 + + + COMP2HYST + Comparator 2 hysteresis + 16 + 2 + + + COMP2_BLANKING + Comparator 2 blanking + source + 18 + 3 + + + COMP2LOCK + Comparator 2 lock + 31 + 1 + + + + + COMP3_CSR + COMP3_CSR + control and status register + 0x24 + 0x20 + 0x0000 + + + COMP3EN + Comparator 3 enable + 0 + 1 + read-write + + + COMP3MODE + Comparator 3 mode + 2 + 2 + read-write + + + COMP3INSEL + Comparator 3 inverting input + selection + 4 + 3 + read-write + + + COMP3INPSEL + Comparator 3 non inverted input + selection + 7 + 1 + read-write + + + COMP3_OUT_SEL + Comparator 3 output + selection + 10 + 4 + read-write + + + COMP3POL + Comparator 3 output + polarity + 15 + 1 + read-write + + + COMP3HYST + Comparator 3 hysteresis + 16 + 2 + read-write + + + COMP3_BLANKING + Comparator 3 blanking + source + 18 + 3 + read-write + + + COMP3OUT + Comparator 3 output + 30 + 1 + read-only + + + COMP3LOCK + Comparator 3 lock + 31 + 1 + read-write + + + + + COMP4_CSR + COMP4_CSR + control and status register + 0x28 + 0x20 + 0x0000 + + + COMP4EN + Comparator 4 enable + 0 + 1 + read-write + + + COMP4MODE + Comparator 4 mode + 2 + 2 + read-write + + + COMP4INSEL + Comparator 4 inverting input + selection + 4 + 3 + read-write + + + COMP4INPSEL + Comparator 4 non inverted input + selection + 7 + 1 + read-write + + + COM4WINMODE + Comparator 4 window mode + 9 + 1 + read-write + + + COMP4_OUT_SEL + Comparator 4 output + selection + 10 + 4 + read-write + + + COMP4POL + Comparator 4 output + polarity + 15 + 1 + read-write + + + COMP4HYST + Comparator 4 hysteresis + 16 + 2 + read-write + + + COMP4_BLANKING + Comparator 4 blanking + source + 18 + 3 + read-write + + + COMP4OUT + Comparator 4 output + 30 + 1 + read-only + + + COMP4LOCK + Comparator 4 lock + 31 + 1 + read-write + + + + + COMP5_CSR + COMP5_CSR + control and status register + 0x2C + 0x20 + 0x0000 + + + COMP5EN + Comparator 5 enable + 0 + 1 + read-write + + + COMP5MODE + Comparator 5 mode + 2 + 2 + read-write + + + COMP5INSEL + Comparator 5 inverting input + selection + 4 + 3 + read-write + + + COMP5INPSEL + Comparator 5 non inverted input + selection + 7 + 1 + read-write + + + COMP5_OUT_SEL + Comparator 5 output + selection + 10 + 4 + read-write + + + COMP5POL + Comparator 5 output + polarity + 15 + 1 + read-write + + + COMP5HYST + Comparator 5 hysteresis + 16 + 2 + read-write + + + COMP5_BLANKING + Comparator 5 blanking + source + 18 + 3 + read-write + + + COMP5OUT + Comparator51 output + 30 + 1 + read-only + + + COMP5LOCK + Comparator 5 lock + 31 + 1 + read-write + + + + + COMP6_CSR + COMP6_CSR + control and status register + 0x30 + 0x20 + 0x0000 + + + COMP6EN + Comparator 6 enable + 0 + 1 + read-write + + + COMP6MODE + Comparator 6 mode + 2 + 2 + read-write + + + COMP6INSEL + Comparator 6 inverting input + selection + 4 + 3 + read-write + + + COMP6INPSEL + Comparator 6 non inverted input + selection + 7 + 1 + read-write + + + COM6WINMODE + Comparator 6 window mode + 9 + 1 + read-write + + + COMP6_OUT_SEL + Comparator 6 output + selection + 10 + 4 + read-write + + + COMP6POL + Comparator 6 output + polarity + 15 + 1 + read-write + + + COMP6HYST + Comparator 6 hysteresis + 16 + 2 + read-write + + + COMP6_BLANKING + Comparator 6 blanking + source + 18 + 3 + read-write + + + COMP6OUT + Comparator 6 output + 30 + 1 + read-only + + + COMP6LOCK + Comparator 6 lock + 31 + 1 + read-write + + + + + COMP7_CSR + COMP7_CSR + control and status register + 0x34 + 0x20 + 0x0000 + + + COMP7EN + Comparator 7 enable + 0 + 1 + read-write + + + COMP7MODE + Comparator 7 mode + 2 + 2 + read-write + + + COMP7INSEL + Comparator 7 inverting input + selection + 4 + 3 + read-write + + + COMP7INPSEL + Comparator 7 non inverted input + selection + 7 + 1 + read-write + + + COMP7_OUT_SEL + Comparator 7 output + selection + 10 + 4 + read-write + + + COMP7POL + Comparator 7 output + polarity + 15 + 1 + read-write + + + COMP7HYST + Comparator 7 hysteresis + 16 + 2 + read-write + + + COMP7_BLANKING + Comparator 7 blanking + source + 18 + 3 + read-write + + + COMP7OUT + Comparator 7 output + 30 + 1 + read-only + + + COMP7LOCK + Comparator 7 lock + 31 + 1 + read-write + + + + + OPAMP1_CSR + OPAMP1_CSR + control register + 0x38 + 0x20 + 0x0000 + + + OPAMP1_EN + OPAMP1 enable + 0 + 1 + read-write + + + FORCE_VP + FORCE_VP + 1 + 1 + read-write + + + VP_SEL + OPAMP1 Non inverting input + selection + 2 + 2 + read-write + + + VM_SEL + OPAMP1 inverting input + selection + 5 + 2 + read-write + + + TCM_EN + Timer controlled Mux mode + enable + 7 + 1 + read-write + + + VMS_SEL + OPAMP1 inverting input secondary + selection + 8 + 1 + read-write + + + VPS_SEL + OPAMP1 Non inverting input secondary + selection + 9 + 2 + read-write + + + CALON + Calibration mode enable + 11 + 1 + read-write + + + CALSEL + Calibration selection + 12 + 2 + read-write + + + PGA_GAIN + Gain in PGA mode + 14 + 4 + read-write + + + USER_TRIM + User trimming enable + 18 + 1 + read-write + + + TRIMOFFSETP + Offset trimming value + (PMOS) + 19 + 5 + read-write + + + TRIMOFFSETN + Offset trimming value + (NMOS) + 24 + 5 + read-write + + + TSTREF + TSTREF + 29 + 1 + read-write + + + OUTCAL + OPAMP 1 ouput status flag + 30 + 1 + read-only + + + LOCK + OPAMP 1 lock + 31 + 1 + read-write + + + + + OPAMP2_CSR + OPAMP2_CSR + control register + 0x3C + 0x20 + 0x0000 + + + OPAMP2EN + OPAMP2 enable + 0 + 1 + read-write + + + FORCE_VP + FORCE_VP + 1 + 1 + read-write + + + VP_SEL + OPAMP2 Non inverting input + selection + 2 + 2 + read-write + + + VM_SEL + OPAMP2 inverting input + selection + 5 + 2 + read-write + + + TCM_EN + Timer controlled Mux mode + enable + 7 + 1 + read-write + + + VMS_SEL + OPAMP2 inverting input secondary + selection + 8 + 1 + read-write + + + VPS_SEL + OPAMP2 Non inverting input secondary + selection + 9 + 2 + read-write + + + CALON + Calibration mode enable + 11 + 1 + read-write + + + CAL_SEL + Calibration selection + 12 + 2 + read-write + + + PGA_GAIN + Gain in PGA mode + 14 + 4 + read-write + + + USER_TRIM + User trimming enable + 18 + 1 + read-write + + + TRIMOFFSETP + Offset trimming value + (PMOS) + 19 + 5 + read-write + + + TRIMOFFSETN + Offset trimming value + (NMOS) + 24 + 5 + read-write + + + TSTREF + TSTREF + 29 + 1 + read-write + + + OUTCAL + OPAMP 2 ouput status flag + 30 + 1 + read-only + + + LOCK + OPAMP 2 lock + 31 + 1 + read-write + + + + + OPAMP3_CSR + OPAMP3_CSR + control register + 0x40 + 0x20 + 0x0000 + + + OPAMP3EN + OPAMP3 enable + 0 + 1 + read-write + + + FORCE_VP + FORCE_VP + 1 + 1 + read-write + + + VP_SEL + OPAMP3 Non inverting input + selection + 2 + 2 + read-write + + + VM_SEL + OPAMP3 inverting input + selection + 5 + 2 + read-write + + + TCM_EN + Timer controlled Mux mode + enable + 7 + 1 + read-write + + + VMS_SEL + OPAMP3 inverting input secondary + selection + 8 + 1 + read-write + + + VPS_SEL + OPAMP3 Non inverting input secondary + selection + 9 + 2 + read-write + + + CALON + Calibration mode enable + 11 + 1 + read-write + + + CALSEL + Calibration selection + 12 + 2 + read-write + + + PGA_GAIN + Gain in PGA mode + 14 + 4 + read-write + + + USER_TRIM + User trimming enable + 18 + 1 + read-write + + + TRIMOFFSETP + Offset trimming value + (PMOS) + 19 + 5 + read-write + + + TRIMOFFSETN + Offset trimming value + (NMOS) + 24 + 5 + read-write + + + TSTREF + TSTREF + 29 + 1 + read-write + + + OUTCAL + OPAMP 3 ouput status flag + 30 + 1 + read-only + + + LOCK + OPAMP 3 lock + 31 + 1 + read-write + + + + + OPAMP4_CSR + OPAMP4_CSR + control register + 0x44 + 0x20 + 0x0000 + + + OPAMP4EN + OPAMP4 enable + 0 + 1 + read-write + + + FORCE_VP + FORCE_VP + 1 + 1 + read-write + + + VP_SEL + OPAMP4 Non inverting input + selection + 2 + 2 + read-write + + + VM_SEL + OPAMP4 inverting input + selection + 5 + 2 + read-write + + + TCM_EN + Timer controlled Mux mode + enable + 7 + 1 + read-write + + + VMS_SEL + OPAMP4 inverting input secondary + selection + 8 + 1 + read-write + + + VPS_SEL + OPAMP4 Non inverting input secondary + selection + 9 + 2 + read-write + + + CALON + Calibration mode enable + 11 + 1 + read-write + + + CALSEL + Calibration selection + 12 + 2 + read-write + + + PGA_GAIN + Gain in PGA mode + 14 + 4 + read-write + + + USER_TRIM + User trimming enable + 18 + 1 + read-write + + + TRIMOFFSETP + Offset trimming value + (PMOS) + 19 + 5 + read-write + + + TRIMOFFSETN + Offset trimming value + (NMOS) + 24 + 5 + read-write + + + TSTREF + TSTREF + 29 + 1 + read-write + + + OUTCAL + OPAMP 4 ouput status flag + 30 + 1 + read-only + + + LOCK + OPAMP 4 lock + 31 + 1 + read-write + + + + + + + FMC + Flexible memory controller + FMC + 0xA0000400 + + 0x0 + 0xC00 + registers + + + FMC + FSMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR2 + PCR2 + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR2 + SR2 + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM2 + PMEM2 + Common memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT2 + PATT2 + Attribute memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR2 + ECCR2 + ECC result register 2 + 0x74 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR3 + PCR3 + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR3 + SR3 + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM3 + PMEM3 + Common memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT3 + PATT3 + Attribute memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR3 + ECCR3 + ECC result register 3 + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR4 + PCR4 + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR4 + SR4 + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM4 + PMEM4 + Common memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT4 + PATT4 + Attribute memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + PIO4 + PIO4 + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IOHIZx + IOHIZx + 24 + 8 + + + IOHOLDx + IOHOLDx + 16 + 8 + + + IOWAITx + IOWAITx + 8 + 8 + + + IOSETx + IOSETx + 0 + 8 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + FPU + Floating point interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CTRL + CTRL + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + LOAD + LOAD + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + VAL + VAL + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + Instruction access violation + flag + 1 + 1 + + + MUNSTKERR + Memory manager fault on unstacking for a + return from exception + 3 + 1 + + + MSTKERR + Memory manager fault on stacking for + exception entry. + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + Memory Management Fault Address Register + (MMAR) valid flag + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + MMFAR + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + BFAR + Bus fault address + 0 + 32 + + + + + AFSR + AFSR + Auxiliary fault status + register + 0x3C + 0x20 + read-write + 0x00000000 + + + IMPDEF + Implementation defined + 0 + 32 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISMCYCINT + DISMCYCINT + 0 + 1 + + + DISDEFWBUF + DISDEFWBUF + 1 + 1 + + + DISFOLD + DISFOLD + 2 + 1 + + + DISFPCA + DISFPCA + 8 + 1 + + + DISOOFP + DISOOFP + 9 + 1 + + + + + + + diff --git a/dev/svd/STM32F405.svd b/dev/svd/STM32F405.svd new file mode 100644 index 00000000000..f5423aa5b47 --- /dev/null +++ b/dev/svd/STM32F405.svd @@ -0,0 +1,61681 @@ + + + STM32F405 + 1.2 + STM32F405 + + + CM4 + r1p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + RNG + Random number generator + RNG + 0x50060800 + + 0x0 + 0x400 + registers + + + FPU + FPU interrupt + 81 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + IE + Interrupt enable + 3 + 1 + + + RNGEN + Random number generator + enable + 2 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + 0x00000000 + + + SEIS + Seed error interrupt + status + 6 + 1 + read-write + + + CEIS + Clock error interrupt + status + 5 + 1 + read-write + + + SECS + Seed error current status + 2 + 1 + read-only + + + CECS + Clock error current status + 1 + 1 + read-only + + + DRDY + Data ready + 0 + 1 + read-only + + + + + DR + DR + data register + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data + 0 + 32 + + + + + + + DCMI + Digital camera interface + DCMI + 0x50050000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ENABLE + DCMI enable + 14 + 1 + + + EDM + Extended data mode + 10 + 2 + + + FCRC + Frame capture rate control + 8 + 2 + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + + + PCKPOL + Pixel clock polarity + 5 + 1 + + + ESS + Embedded synchronization + select + 4 + 1 + + + JPEG + JPEG format + 3 + 1 + + + CROP + Crop feature + 2 + 1 + + + CM + Capture mode + 1 + 1 + + + CAPTURE + Capture enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + FSMC + Flexible static memory controller + FSMC + 0xA0000000 + + 0x0 + 0x400 + registers + + + FSMC + FSMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR2 + PCR2 + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR2 + SR2 + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM2 + PMEM2 + Common memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT2 + PATT2 + Attribute memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR2 + ECCR2 + ECC result register 2 + 0x74 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR3 + PCR3 + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR3 + SR3 + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM3 + PMEM3 + Common memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT3 + PATT3 + Attribute memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR3 + ECCR3 + ECC result register 3 + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR4 + PCR4 + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR4 + SR4 + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM4 + PMEM4 + Common memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT4 + PATT4 + Attribute memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + PIO4 + PIO4 + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IOHIZx + IOHIZx + 24 + 8 + + + IOHOLDx + IOHOLDx + 16 + 8 + + + IOWAITx + IOWAITx + 8 + 8 + + + IOSETx + IOSETx + 0 + 8 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + DBG_I2C2_SMBUS_TIMEOUT + DBG_I2C2_SMBUS_TIMEOUT + 16 + 1 + + + DBG_TIM8_STOP + DBG_TIM8_STOP + 17 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 18 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 19 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 20 + 1 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + ETHMACRST + Ethernet MAC reset + 25 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOIRST + IO port I reset + 8 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + RNGRST + Random number generator module + reset + 6 + 1 + + + DCMIRST + Camera interface reset + 0 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FSMCRST + Flexible static memory controller module + reset + 0 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACRST + DAC reset + 29 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM2RST + TIM2 reset + 0 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM11RST + TIM11 reset + 18 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SDIORST + SDIO reset + 11 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + TIM1RST + TIM1 reset + 0 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + ETHMACPTPEN + Ethernet PTP clock enable + 28 + 1 + + + ETHMACRXEN + Ethernet Reception clock + enable + 27 + 1 + + + ETHMACTXEN + Ethernet Transmission clock + enable + 26 + 1 + + + ETHMACEN + Ethernet MAC clock enable + 25 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOIEN + IO port I clock enable + 8 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + RNGEN + Random number generator clock + enable + 6 + 1 + + + DCMIEN + Camera interface enable + 0 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FSMCEN + Flexible static memory controller module + clock enable + 0 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + DACEN + DAC interface clock enable + 29 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + CAN2EN + CAN 2 clock enable + 26 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SDIOEN + SDIO clock enable + 11 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + ETHMACPTPLPEN + Ethernet PTP clock enable during Sleep + mode + 28 + 1 + + + ETHMACRXLPEN + Ethernet reception clock enable during + Sleep mode + 27 + 1 + + + ETHMACTXLPEN + Ethernet transmission clock enable + during Sleep mode + 26 + 1 + + + ETHMACLPEN + Ethernet MAC clock enable during Sleep + mode + 25 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + GPIOILPEN + IO port I clock enable during Sleep + mode + 8 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + RNGLPEN + Random number generator clock enable + during Sleep mode + 6 + 1 + + + DCMILPEN + Camera interface enable during Sleep + mode + 0 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FSMCLPEN + Flexible static memory controller module + clock enable during Sleep mode + 0 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SDIOLPEN + SDIO clock enable during Sleep + mode + 11 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SRx + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SNx + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + + + GPIOI + General-purpose I/Os + GPIO + 0x40022000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOH + 0x40021C00 + + + GPIOG + 0x40021800 + + + GPIOF + 0x40021400 + + + GPIOE + 0x40021000 + + + GPIOD + 0X40020C00 + + + GPIOC + 0x40020800 + + + GPIOJ + 0x40022400 + + + GPIOK + 0x40022800 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + MEM_MODE + 0 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + Ethernet PHY interface + selection + 23 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + DFF + Data frame format + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + FRF + Frame format + 4 + 1 + + + SSOE + SS output enable + 2 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + TIFRFE + TI frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + I2S2ext + 0x40003400 + + + I2S3ext + 0x40004000 + + + SPI4 + 0x40013400 + + SPI1 + SPI1 global interrupt + 35 + + + + SPI5 + 0x40015000 + + SPI1 + SPI1 global interrupt + 35 + + + + SPI6 + 0x40015400 + + SPI3 + SPI3 global interrupt + 51 + + + + SDIO + Secure digital input/output + interface + SDIO + 0x40012C00 + + 0x0 + 0x400 + registers + + + SDIO + SDIO global interrupt + 49 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + CE_ATACMD + CE-ATA command + 14 + 1 + + + nIEN + not Interrupt Enable + 13 + 1 + + + ENCMDcompl + Enable CMD completion + 12 + 1 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal). + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 132. + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table 132. + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table 132. + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table 132. + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer. + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + CEATAEND + CE-ATA command completion signal + received for CMD61 + 23 + 1 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + STBITERR + Start bit not detected on all data + signals in wide bus mode + 9 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEATAENDC + CEATAEND flag clear bit + 23 + 1 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + STBITERRC + STBITERR flag clear bit + 9 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + CEATAENDIE + CE-ATA command completion signal + received interrupt enable + 23 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + STBITERRIE + Start bit error interrupt + enable + 9 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO. + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x51 + registers + + + ADC + ADC1 global interrupt + 18 + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC2 + 0x40012100 + + ADC + ADC2 global interrupts + 18 + + + + ADC3 + 0x40012200 + + ADC + ADC3 global interrupts + 18 + + + + USART6 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011400 + + 0x0 + 0x400 + registers + + + USART6 + USART6 global interrupt + 71 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + CTS + CTS flag + 9 + 1 + read-write + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x18 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + + + USART1 + 0x40011000 + + USART1 + USART1 global interrupt + 37 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + PVD + PVD through EXTI line detection + interrupt + 1 + + + + CR + CR + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + PLS + PVD level selection + 5 + 3 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + CWUF + Clear wakeup flag + 2 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + LPDS + Low-power deep sleep + 0 + 1 + + + + + CSR + CSR + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUF + Wakeup flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + EWUP + Enable WKUP pin + 8 + 1 + read-write + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + + + + + I2C3 + Inter-integrated circuit + I2C + 0x40005C00 + + 0x0 + 0x400 + registers + + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SWRST + Software reset + 15 + 1 + + + ALERT + SMBus alert + 13 + 1 + + + PEC + Packet error checking + 12 + 1 + + + POS + Acknowledge/PEC Position (for data + reception) + 11 + 1 + + + ACK + Acknowledge enable + 10 + 1 + + + STOP + Stop generation + 9 + 1 + + + START + Start generation + 8 + 1 + + + NOSTRETCH + Clock stretching disable (Slave + mode) + 7 + 1 + + + ENGC + General call enable + 6 + 1 + + + ENPEC + PEC enable + 5 + 1 + + + ENARP + ARP enable + 4 + 1 + + + SMBTYPE + SMBus type + 3 + 1 + + + SMBUS + SMBus mode + 1 + 1 + + + PE + Peripheral enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + LAST + DMA last transfer + 12 + 1 + + + DMAEN + DMA requests enable + 11 + 1 + + + ITBUFEN + Buffer interrupt enable + 10 + 1 + + + ITEVTEN + Event interrupt enable + 9 + 1 + + + ITERREN + Error interrupt enable + 8 + 1 + + + FREQ + Peripheral clock frequency + 0 + 6 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + ADDMODE + Addressing mode (slave + mode) + 15 + 1 + + + ADD10 + Interface address + 8 + 2 + + + ADD7 + Interface address + 1 + 7 + + + ADD0 + Interface address + 0 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x0000 + + + ADD2 + Interface address + 1 + 7 + + + ENDUAL + Dual addressing mode + enable + 0 + 1 + + + + + DR + DR + Data register + 0x10 + 0x20 + read-write + 0x0000 + + + DR + 8-bit data register + 0 + 8 + + + + + SR1 + SR1 + Status register 1 + 0x14 + 0x20 + 0x0000 + + + SMBALERT + SMBus alert + 15 + 1 + read-write + + + TIMEOUT + Timeout or Tlow error + 14 + 1 + read-write + + + PECERR + PEC Error in reception + 12 + 1 + read-write + + + OVR + Overrun/Underrun + 11 + 1 + read-write + + + AF + Acknowledge failure + 10 + 1 + read-write + + + ARLO + Arbitration lost (master + mode) + 9 + 1 + read-write + + + BERR + Bus error + 8 + 1 + read-write + + + TxE + Data register empty + (transmitters) + 7 + 1 + read-only + + + RxNE + Data register not empty + (receivers) + 6 + 1 + read-only + + + STOPF + Stop detection (slave + mode) + 4 + 1 + read-only + + + ADD10 + 10-bit header sent (Master + mode) + 3 + 1 + read-only + + + BTF + Byte transfer finished + 2 + 1 + read-only + + + ADDR + Address sent (master mode)/matched + (slave mode) + 1 + 1 + read-only + + + SB + Start bit (Master mode) + 0 + 1 + read-only + + + + + SR2 + SR2 + Status register 2 + 0x18 + 0x20 + read-only + 0x0000 + + + PEC + acket error checking + register + 8 + 8 + + + DUALF + Dual flag (Slave mode) + 7 + 1 + + + SMBHOST + SMBus host header (Slave + mode) + 6 + 1 + + + SMBDEFAULT + SMBus device default address (Slave + mode) + 5 + 1 + + + GENCALL + General call address (Slave + mode) + 4 + 1 + + + TRA + Transmitter/receiver + 2 + 1 + + + BUSY + Bus busy + 1 + 1 + + + MSL + Master/slave + 0 + 1 + + + + + CCR + CCR + Clock control register + 0x1C + 0x20 + read-write + 0x0000 + + + F_S + I2C master mode selection + 15 + 1 + + + DUTY + Fast mode duty cycle + 14 + 1 + + + CCR + Clock control register in Fast/Standard + mode (Master mode) + 0 + 12 + + + + + TRISE + TRISE + TRISE register + 0x20 + 0x20 + read-write + 0x0002 + + + TRISE + Maximum rise time in Fast/Standard mode + (Master mode) + 0 + 6 + + + + + + + I2C2 + 0x40005800 + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2C1 + 0x40005400 + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTC_Alarm + RTC Alarms (A and B) through EXTI line + interrupt + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + COE + Calibration output enable + 23 + 1 + + + OSEL + Output selection + 21 + 2 + + + POL + Output polarity + 20 + 1 + + + BKP + Backup + 18 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + DCE + Coarse digital calibration + enable + 7 + 1 + + + FMT + Hour format + 6 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + TAMPER2 detection flag + 14 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + CALIBR + CALIBR + calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + DCS + Digital calibration sign + 7 + 1 + + + DC + Digital calibration + 0 + 5 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAFCR + TAFCR + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + UART4 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40004C00 + + 0x0 + 0x400 + registers + + + UART4 + UART4 global interrupt + 52 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + UART7 + 0x40007800 + + UART4 + UART4 global interrupt + 52 + + + + UART8 + 0x40007C00 + + UART5 + UART5 global interrupt + 53 + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0x400 + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + + + TIM8 + 0x40010400 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + ITR1_RMP + Timer Input 4 remap + 10 + 2 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM4 + 0x40000800 + + TIM4 + TIM4 global interrupt + 30 + + + + TIM5 + General-purpose-timers + TIM + 0x40000C00 + + 0x0 + 0x400 + registers + + + TIM5 + TIM5 global interrupt + 50 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + IT4_RMP + Timer Input 4 remap + 6 + 2 + + + + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + + + TIM13 + 0x40001C00 + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + + TIM14 + 0x40002000 + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + + TIM11 + General-purpose-timers + TIM + 0x40014800 + + 0x0 + 0x400 + registers + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + RMP + Input 1 remapping + capability + 0 + 2 + + + + + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + Ethernet_MAC + Ethernet: media access control + (MAC) + Ethernet + 0x40028000 + + 0x0 + 0x61 + registers + + + ETH + Ethernet global interrupt + 61 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + + MACCR + MACCR + Ethernet MAC configuration + register + 0x0 + 0x20 + read-write + 0x0008000 + + + RE + RE + 2 + 1 + + + TE + TE + 3 + 1 + + + DC + DC + 4 + 1 + + + BL + BL + 5 + 2 + + + APCS + APCS + 7 + 1 + + + RD + RD + 9 + 1 + + + IPCO + IPCO + 10 + 1 + + + DM + DM + 11 + 1 + + + LM + LM + 12 + 1 + + + ROD + ROD + 13 + 1 + + + FES + FES + 14 + 1 + + + CSD + CSD + 16 + 1 + + + IFG + IFG + 17 + 3 + + + JD + JD + 22 + 1 + + + WD + WD + 23 + 1 + + + CSTF + CSTF + 25 + 1 + + + + + MACFFR + MACFFR + Ethernet MAC frame filter + register + 0x4 + 0x20 + read-write + 0x00000000 + + + PM + PM + 0 + 1 + + + HU + HU + 1 + 1 + + + HM + HM + 2 + 1 + + + DAIF + DAIF + 3 + 1 + + + RAM + RAM + 4 + 1 + + + BFD + BFD + 5 + 1 + + + PCF + PCF + 6 + 1 + + + SAIF + SAIF + 7 + 1 + + + SAF + SAF + 8 + 1 + + + HPF + HPF + 9 + 1 + + + RA + RA + 31 + 1 + + + + + MACHTHR + MACHTHR + Ethernet MAC hash table high + register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + HTH + 0 + 32 + + + + + MACHTLR + MACHTLR + Ethernet MAC hash table low + register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + HTL + 0 + 32 + + + + + MACMIIAR + MACMIIAR + Ethernet MAC MII address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MB + 0 + 1 + + + MW + MW + 1 + 1 + + + CR + CR + 2 + 3 + + + MR + MR + 6 + 5 + + + PA + PA + 11 + 5 + + + + + MACMIIDR + MACMIIDR + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + TD + TD + 0 + 16 + + + + + MACFCR + MACFCR + Ethernet MAC flow control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB + FCB + 0 + 1 + + + TFCE + TFCE + 1 + 1 + + + RFCE + RFCE + 2 + 1 + + + UPFD + UPFD + 3 + 1 + + + PLT + PLT + 4 + 2 + + + ZQPD + ZQPD + 7 + 1 + + + PT + PT + 16 + 16 + + + + + MACVLANTR + MACVLANTR + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VLANTI + VLANTI + 0 + 16 + + + VLANTC + VLANTC + 16 + 1 + + + + + MACPMTCSR + MACPMTCSR + Ethernet MAC PMT control and status + register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + PD + 0 + 1 + + + MPE + MPE + 1 + 1 + + + WFE + WFE + 2 + 1 + + + MPR + MPR + 5 + 1 + + + WFR + WFR + 6 + 1 + + + GU + GU + 9 + 1 + + + WFFRPR + WFFRPR + 31 + 1 + + + + + MACDBGR + MACDBGR + Ethernet MAC debug register + 0x34 + 0x20 + read-only + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MACSR + MACSR + Ethernet MAC interrupt status + register + 0x38 + 0x20 + 0x00000000 + + + PMTS + PMTS + 3 + 1 + read-only + + + MMCS + MMCS + 4 + 1 + read-only + + + MMCRS + MMCRS + 5 + 1 + read-only + + + MMCTS + MMCTS + 6 + 1 + read-only + + + TSTS + TSTS + 9 + 1 + read-write + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask + register + 0x3C + 0x20 + read-write + 0x00000000 + + + PMTIM + PMTIM + 3 + 1 + + + TSTIM + TSTIM + 9 + 1 + + + + + MACA0HR + MACA0HR + Ethernet MAC address 0 high + register + 0x40 + 0x20 + 0x0010FFFF + + + MACA0H + MAC address0 high + 0 + 16 + read-write + + + MO + Always 1 + 31 + 1 + read-only + + + + + MACA0LR + MACA0LR + Ethernet MAC address 0 low + register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MACA0L + 0 + 0 + 32 + + + + + MACA1HR + MACA1HR + Ethernet MAC address 1 high + register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MACA1H + MACA1H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA1LR + MACA1LR + Ethernet MAC address1 low + register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MACA1LR + MACA1LR + 0 + 32 + + + + + MACA2HR + MACA2HR + Ethernet MAC address 2 high + register + 0x50 + 0x20 + read-write + 0x0000FFFF + + + MAC2AH + MAC2AH + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA2LR + MACA2LR + Ethernet MAC address 2 low + register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MACA2L + MACA2L + 0 + 31 + + + + + MACA3HR + MACA3HR + Ethernet MAC address 3 high + register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MACA3H + MACA3H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3LR + MACA3LR + Ethernet MAC address 3 low + register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MBCA3L + MBCA3L + 0 + 32 + + + + + + + Ethernet_MMC + Ethernet: MAC management counters + Ethernet + 0x40028100 + + 0x0 + 0x400 + registers + + + + MMCCR + MMCCR + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MMCRIR + MMCRIR + Ethernet MMC receive interrupt + register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCES + RFCES + 5 + 1 + + + RFAES + RFAES + 6 + 1 + + + RGUFS + RGUFS + 17 + 1 + + + + + MMCTIR + MMCTIR + Ethernet MMC transmit interrupt + register + 0x8 + 0x20 + read-only + 0x00000000 + + + TGFSCS + TGFSCS + 14 + 1 + + + TGFMSCS + TGFMSCS + 15 + 1 + + + TGFS + TGFS + 21 + 1 + + + + + MMCRIMR + MMCRIMR + Ethernet MMC receive interrupt mask + register + 0xC + 0x20 + read-write + 0x00000000 + + + RFCEM + RFCEM + 5 + 1 + + + RFAEM + RFAEM + 6 + 1 + + + RGUFM + RGUFM + 17 + 1 + + + + + MMCTIMR + MMCTIMR + Ethernet MMC transmit interrupt mask + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TGFSCM + TGFSCM + 14 + 1 + + + TGFMSCM + TGFMSCM + 15 + 1 + + + TGFM + TGFM + 16 + 1 + + + + + MMCTGFSCCR + MMCTGFSCCR + Ethernet MMC transmitted good frames after a + single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + TGFSCC + 0 + 32 + + + + + MMCTGFMSCCR + MMCTGFMSCCR + Ethernet MMC transmitted good frames after + more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + TGFMSCC + 0 + 32 + + + + + MMCTGFCR + MMCTGFCR + Ethernet MMC transmitted good frames counter + register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + HTL + 0 + 32 + + + + + MMCRFCECR + MMCRFCECR + Ethernet MMC received frames with CRC error + counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCFC + RFCFC + 0 + 32 + + + + + MMCRFAECR + MMCRFAECR + Ethernet MMC received frames with alignment + error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + RFAEC + 0 + 32 + + + + + MMCRGUFCR + MMCRGUFCR + MMC received good unicast frames counter + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + RGUFC + 0 + 32 + + + + + + + Ethernet_PTP + Ethernet: Precision time protocol + Ethernet + 0x40028700 + + 0x0 + 0x400 + registers + + + + PTPTSCR + PTPTSCR + Ethernet PTP time stamp control + register + 0x0 + 0x20 + read-write + 0x00002000 + + + TSE + TSE + 0 + 1 + + + TSFCU + TSFCU + 1 + 1 + + + TSPTPPSV2E + TSPTPPSV2E + 10 + 1 + + + TSSPTPOEFE + TSSPTPOEFE + 11 + 1 + + + TSSIPV6FE + TSSIPV6FE + 12 + 1 + + + TSSIPV4FE + TSSIPV4FE + 13 + 1 + + + TSSEME + TSSEME + 14 + 1 + + + TSSMRME + TSSMRME + 15 + 1 + + + TSCNT + TSCNT + 16 + 2 + + + TSPFFMAE + TSPFFMAE + 18 + 1 + + + TSSTI + TSSTI + 2 + 1 + + + TSSTU + TSSTU + 3 + 1 + + + TSITE + TSITE + 4 + 1 + + + TTSARU + TTSARU + 5 + 1 + + + TSSARFE + TSSARFE + 8 + 1 + + + TSSSR + TSSSR + 9 + 1 + + + + + PTPSSIR + PTPSSIR + Ethernet PTP subsecond increment + register + 0x4 + 0x20 + read-write + 0x00000000 + + + STSSI + STSSI + 0 + 8 + + + + + PTPTSHR + PTPTSHR + Ethernet PTP time stamp high + register + 0x8 + 0x20 + read-only + 0x00000000 + + + STS + STS + 0 + 32 + + + + + PTPTSLR + PTPTSLR + Ethernet PTP time stamp low + register + 0xC + 0x20 + read-only + 0x00000000 + + + STSS + STSS + 0 + 31 + + + STPNS + STPNS + 31 + 1 + + + + + PTPTSHUR + PTPTSHUR + Ethernet PTP time stamp high update + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSUS + TSUS + 0 + 32 + + + + + PTPTSLUR + PTPTSLUR + Ethernet PTP time stamp low update + register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSUSS + TSUSS + 0 + 31 + + + TSUPNS + TSUPNS + 31 + 1 + + + + + PTPTSAR + PTPTSAR + Ethernet PTP time stamp addend + register + 0x18 + 0x20 + read-write + 0x00000000 + + + TSA + TSA + 0 + 32 + + + + + PTPTTHR + PTPTTHR + Ethernet PTP target time high + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSH + 0 + 0 + 32 + + + + + PTPTTLR + PTPTTLR + Ethernet PTP target time low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTSL + TTSL + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status + register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control + register + 0x2C + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + + + Ethernet_DMA + Ethernet: DMA controller operation + Ethernet + 0x40029000 + + 0x0 + 0x400 + registers + + + + DMABMR + DMABMR + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x00002101 + + + SR + SR + 0 + 1 + + + DA + DA + 1 + 1 + + + DSL + DSL + 2 + 5 + + + EDFE + EDFE + 7 + 1 + + + PBL + PBL + 8 + 6 + + + RTPR + RTPR + 14 + 2 + + + FB + FB + 16 + 1 + + + RDP + RDP + 17 + 6 + + + USP + USP + 23 + 1 + + + FPM + FPM + 24 + 1 + + + AAB + AAB + 25 + 1 + + + MB + MB + 26 + 1 + + + + + DMATPDR + DMATPDR + Ethernet DMA transmit poll demand + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + TPD + 0 + 32 + + + + + DMARPDR + DMARPDR + EHERNET DMA receive poll demand + register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + RPD + 0 + 32 + + + + + DMARDLAR + DMARDLAR + Ethernet DMA receive descriptor list address + register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + SRL + 0 + 32 + + + + + DMATDLAR + DMATDLAR + Ethernet DMA transmit descriptor list + address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + STL + 0 + 32 + + + + + DMASR + DMASR + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TS + TS + 0 + 1 + read-write + + + TPSS + TPSS + 1 + 1 + read-write + + + TBUS + TBUS + 2 + 1 + read-write + + + TJTS + TJTS + 3 + 1 + read-write + + + ROS + ROS + 4 + 1 + read-write + + + TUS + TUS + 5 + 1 + read-write + + + RS + RS + 6 + 1 + read-write + + + RBUS + RBUS + 7 + 1 + read-write + + + RPSS + RPSS + 8 + 1 + read-write + + + PWTS + PWTS + 9 + 1 + read-write + + + ETS + ETS + 10 + 1 + read-write + + + FBES + FBES + 13 + 1 + read-write + + + ERS + ERS + 14 + 1 + read-write + + + AIS + AIS + 15 + 1 + read-write + + + NIS + NIS + 16 + 1 + read-write + + + RPS + RPS + 17 + 3 + read-only + + + TPS + TPS + 20 + 3 + read-only + + + EBS + EBS + 23 + 3 + read-only + + + MMCS + MMCS + 27 + 1 + read-only + + + PMTS + PMTS + 28 + 1 + read-only + + + TSTS + TSTS + 29 + 1 + read-only + + + + + DMAOMR + DMAOMR + Ethernet DMA operation mode + register + 0x18 + 0x20 + read-write + 0x00000000 + + + SR + SR + 1 + 1 + + + OSF + OSF + 2 + 1 + + + RTC + RTC + 3 + 2 + + + FUGF + FUGF + 6 + 1 + + + FEF + FEF + 7 + 1 + + + ST + ST + 13 + 1 + + + TTC + TTC + 14 + 3 + + + FTF + FTF + 20 + 1 + + + TSF + TSF + 21 + 1 + + + DFRF + DFRF + 24 + 1 + + + RSF + RSF + 25 + 1 + + + DTCEFD + DTCEFD + 26 + 1 + + + + + DMAIER + DMAIER + Ethernet DMA interrupt enable + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + TIE + 0 + 1 + + + TPSIE + TPSIE + 1 + 1 + + + TBUIE + TBUIE + 2 + 1 + + + TJTIE + TJTIE + 3 + 1 + + + ROIE + ROIE + 4 + 1 + + + TUIE + TUIE + 5 + 1 + + + RIE + RIE + 6 + 1 + + + RBUIE + RBUIE + 7 + 1 + + + RPSIE + RPSIE + 8 + 1 + + + RWTIE + RWTIE + 9 + 1 + + + ETIE + ETIE + 10 + 1 + + + FBEIE + FBEIE + 13 + 1 + + + ERIE + ERIE + 14 + 1 + + + AISE + AISE + 15 + 1 + + + NISE + NISE + 16 + 1 + + + + + DMAMFBOCR + DMAMFBOCR + Ethernet DMA missed frame and buffer + overflow counter register + 0x20 + 0x20 + read-write + 0x00000000 + + + MFC + MFC + 0 + 16 + + + OMFC + OMFC + 16 + 1 + + + MFA + MFA + 17 + 11 + + + OFOC + OFOC + 28 + 1 + + + + + DMARSWTR + DMARSWTR + Ethernet DMA receive status watchdog timer + register + 0x24 + 0x20 + read-write + 0x00000000 + + + RSWTC + RSWTC + 0 + 8 + + + + + DMACHTDR + DMACHTDR + Ethernet DMA current host transmit + descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + HTDAP + 0 + 32 + + + + + DMACHRDR + DMACHRDR + Ethernet DMA current host receive descriptor + register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + HRDAP + 0 + 32 + + + + + DMACHTBAR + DMACHTBAR + Ethernet DMA current host transmit buffer + address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + HTBAP + 0 + 32 + + + + + DMACHRBAR + DMACHRBAR + Ethernet DMA current host receive buffer + address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + HRBAP + 0 + 32 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + FS_GOTGCTL + FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + FS_GOTGINT + FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + FS_GAHBCFG + FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + FS_GUSBCFG + FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + FS_GRSTCTL + FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + FS_GINTSTS + FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + FS_GINTMSK + FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + FS_GRXSTSR_Device + FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXSTSR_Host + FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXFSIZ + FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + FS_GNPTXFSIZ_Device + FS_GNPTXFSIZ_Device + OTG_FS non-periodic transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + FS_GNPTXFSIZ_Host + FS_GNPTXFSIZ_Host + OTG_FS non-periodic transmit FIFO size + register (Host mode) + FS_GNPTXFSIZ_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + FS_GNPTXSTS + FS_GNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + FS_GCCFG + FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + + + FS_CID + FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + FS_HPTXFSIZ + FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF1 + FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF2 + FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF3 + FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + + FS_HCFG + FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + FS_HFNUM + FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + FS_HPTXSTS + FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + FS_HPRT + FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + FS_HCCHAR0 + FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR1 + FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR2 + FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR3 + FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR4 + FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR5 + FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR6 + FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR7 + FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCINT0 + FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT1 + FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT2 + FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT3 + FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT4 + FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT5 + FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT6 + FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT7 + FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINTMSK0 + FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK1 + FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK2 + FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK3 + FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK4 + FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK5 + FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK6 + FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK7 + FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCTSIZ0 + FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ1 + FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ2 + FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ3 + FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ4 + FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ5 + FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ6 + FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ7 + FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + FS_DCFG + FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + FS_DCTL + FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + FS_DSTS + FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + FS_DIEPMSK + FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + FS_DOEPMSK + FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + FS_DAINT + FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + FS_DAINTMSK + FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DVBUSDIS + DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + DVBUSPULSE + DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + FS_DIEPCTL0 + FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + DOEPCTL1 + DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPINT0 + DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT1 + DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT2 + DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT3 + DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DOEPINT0 + DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT1 + DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT2 + DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT3 + DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DTXFSTS0 + DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + + FS_PCGCCTL + FS_PCGCCTL + OTG_FS power and clock gating control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2SB + 8 + 6 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + 0x00000000 + + + LATENCY + Latency + 0 + 3 + read-write + + + PRFTEN + Prefetch enable + 8 + 1 + read-write + + + ICEN + Instruction cache enable + 9 + 1 + read-write + + + DCEN + Data cache enable + 10 + 1 + read-write + + + ICRST + Instruction cache reset + 11 + 1 + write-only + + + DCRST + Data cache reset + 12 + 1 + read-write + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + PGSERR + Programming sequence error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase + 2 + 1 + + + SNB + Sector number + 3 + 4 + + + PSIZE + Program size + 8 + 2 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x00000014 + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WDG_SW + WDG_SW User option bytes + 5 + 1 + + + nRST_STOP + nRST_STOP User option + bytes + 6 + 1 + + + nRST_STDBY + nRST_STDBY User option + bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 12 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x131 + registers + + + OTG_HS_EP1_OUT + USB On The Go HS End Point 1 Out global + interrupt + 74 + + + OTG_HS_EP1_IN + USB On The Go HS End Point 1 In global + interrupt + 75 + + + OTG_HS_WKUP + USB On The Go HS Wakeup through EXTI + interrupt + 76 + + + OTG_HS + USB On The Go HS global + interrupt + 77 + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + DMAREQ + DMA request signal + 30 + 1 + read-only + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_GNPTXFSIZ_Host + OTG_HS_GNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_TX0FSIZ_Peripheral + OTG_HS_TX0FSIZ_Peripheral + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_GNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + I2CPADEN + Enable I2C bus connection for the + external I2C PHY interface + 17 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + NOVBUSSENS + VBUS sensing disable + option + 21 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Peripheral + OTG_HS_GRXSTSR_Peripheral + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Peripheral + OTG_HS_GRXSTSP_Peripheral + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPEACHMSK1 + OTG_HS_DIEPEACHMSK1 + OTG_HS device each in endpoint-1 interrupt + register + 0x40 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + + + OTG_HS_DOEPEACHMSK1 + OTG_HS_DOEPEACHMSK1 + OTG_HS device each OUT endpoint-1 interrupt + register + 0x80 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + OUT packet error mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + BERRM + Bubble error interrupt + mask + 12 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + NYETM + NYET interrupt mask + 14 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-1 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-2 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-3 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-4 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-5 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x351 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + SAI1 + Serial audio interface + SAI1 + 0x40015800 + + 0x0 + 0x400 + registers + + + + SAI_ACR1 + SAI_ACR1 + SAI AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCKDIV + Master clock divider + 20 + 4 + + + MODE + Audio block mode + 0 + 2 + + + PRTCFG + Protocol configuration + 2 + 2 + + + DS + Data size + 5 + 3 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + CKSTR + Clock strobing edge + 9 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + MONO + Mono mode + 12 + 1 + + + OUTDRIV + Output drive + 13 + 1 + + + SAIAEN + Audio block enable + 16 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + NODIV + No divider + 19 + 1 + + + + + SAI_BCR1 + SAI_BCR1 + SAI BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MODE + Audio block mode + 0 + 2 + + + PRTCFG + Protocol configuration + 2 + 2 + + + DS + Data size + 5 + 3 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + CKSTR + Clock strobing edge + 9 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + MONO + Mono mode + 12 + 1 + + + OUTDRIV + Output drive + 13 + 1 + + + SAIBEN + Audio block enable + 16 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + NODIV + No divider + 19 + 1 + + + MCKDIV + Master clock divider + 20 + 4 + + + + + SAI_ACR2 + SAI_ACR2 + SAI AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000040 + + + FTH + FIFO threshold + 0 + 3 + + + FFLUSH + FIFO flush + 3 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + MUTE + Mute + 5 + 1 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTECNT + Mute counter + 7 + 6 + + + CPL + Complement bit + 13 + 1 + + + COMP + Companding mode + 14 + 2 + + + + + SAI_BCR2 + SAI_BCR2 + SAI BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000040 + + + FTH + FIFO threshold + 0 + 3 + + + FFLUSH + FIFO flush + 3 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + MUTE + Mute + 5 + 1 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTECNT + Mute counter + 7 + 6 + + + CPL + Complement bit + 13 + 1 + + + COMP + Companding mode + 14 + 2 + + + + + SAI_AFRCR + SAI_AFRCR + SAI AFrame configuration + register + 0xC + 0x20 + 0x00000007 + + + FRL + Frame length + 0 + 8 + read-write + + + FSALL + Frame synchronization active level + length + 8 + 7 + read-write + + + FSDEF + Frame synchronization + definition + 16 + 1 + read-only + + + FSPOL + Frame synchronization + polarity + 17 + 1 + read-write + + + FSOFF + Frame synchronization + offset + 18 + 1 + read-write + + + + + SAI_BFRCR + SAI_BFRCR + SAI BFrame configuration + register + 0x2C + 0x20 + 0x00000007 + + + FRL + Frame length + 0 + 8 + read-write + + + FSALL + Frame synchronization active level + length + 8 + 7 + read-write + + + FSDEF + Frame synchronization + definition + 16 + 1 + read-only + + + FSPOL + Frame synchronization + polarity + 17 + 1 + read-write + + + FSOFF + Frame synchronization + offset + 18 + 1 + read-write + + + + + SAI_ASLOTR + SAI_ASLOTR + SAI ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + FBOFF + First bit offset + 0 + 5 + + + SLOTSZ + Slot size + 6 + 2 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTEN + Slot enable + 16 + 16 + + + + + SAI_BSLOTR + SAI_BSLOTR + SAI BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + FBOFF + First bit offset + 0 + 5 + + + SLOTSZ + Slot size + 6 + 2 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTEN + Slot enable + 16 + 16 + + + + + SAI_AIM + SAI_AIM + SAI AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + MUTEDETIE + Mute detection interrupt + enable + 1 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable + 2 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + + + SAI_BIM + SAI_BIM + SAI BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + MUTEDETIE + Mute detection interrupt + enable + 1 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable + 2 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + + + SAI_ASR + SAI_ASR + SAI AStatus register + 0x18 + 0x20 + read-only + 0x00000008 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + FREQ + FIFO request + 3 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + FLTH + FIFO level threshold + 16 + 3 + + + + + SAI_BSR + SAI_BSR + SAI BStatus register + 0x38 + 0x20 + read-only + 0x00000008 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + FREQ + FIFO request + 3 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + FLTH + FIFO level threshold + 16 + 3 + + + + + SAI_ACLRFR + SAI_ACLRFR + SAI AClear flag register + 0x1C + 0x20 + read-write + 0x00000000 + + + COVRUDR + Clear overrun / underrun + 0 + 1 + + + CMUTEDET + Mute detection flag + 1 + 1 + + + CWCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + CCNRDY + Clear codec not ready flag + 4 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CLFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + + + SAI_BCLRFR + SAI_BCLRFR + SAI BClear flag register + 0x3C + 0x20 + read-write + 0x00000000 + + + COVRUDR + Clear overrun / underrun + 0 + 1 + + + CMUTEDET + Mute detection flag + 1 + 1 + + + CWCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + CCNRDY + Clear codec not ready flag + 4 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CLFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + + + SAI_ADR + SAI_ADR + SAI AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + SAI_BDR + SAI_BDR + SAI BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + + + LTDC + LCD-TFT Controller + LTDC + 0x40016800 + + 0x0 + 0x400 + registers + + + LCD_TFT + LTDC global interrupt + 88 + + + LCD_TFT_1 + LTDC global error interrupt + 89 + + + + SSCR + SSCR + Synchronization Size Configuration + Register + 0x8 + 0x20 + read-write + 0x00000000 + + + HSW + Horizontal Synchronization Width (in + units of pixel clock period) + 16 + 10 + + + VSH + Vertical Synchronization Height (in + units of horizontal scan line) + 0 + 11 + + + + + BPCR + BPCR + Back Porch Configuration + Register + 0xC + 0x20 + read-write + 0x00000000 + + + AHBP + Accumulated Horizontal back porch (in + units of pixel clock period) + 16 + 10 + + + AVBP + Accumulated Vertical back porch (in + units of horizontal scan line) + 0 + 11 + + + + + AWCR + AWCR + Active Width Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + AAV + AAV + 16 + 10 + + + AAH + Accumulated Active Height (in units of + horizontal scan line) + 0 + 11 + + + + + TWCR + TWCR + Total Width Configuration + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTALW + Total Width (in units of pixel clock + period) + 16 + 10 + + + TOTALH + Total Height (in units of horizontal + scan line) + 0 + 11 + + + + + GCR + GCR + Global Control Register + 0x18 + 0x20 + 0x00002220 + + + HSPOL + Horizontal Synchronization + Polarity + 31 + 1 + read-write + + + VSPOL + Vertical Synchronization + Polarity + 30 + 1 + read-write + + + DEPOL + Data Enable Polarity + 29 + 1 + read-write + + + PCPOL + Pixel Clock Polarity + 28 + 1 + read-write + + + DEN + Dither Enable + 16 + 1 + read-write + + + DRW + Dither Red Width + 12 + 3 + read-only + + + DGW + Dither Green Width + 8 + 3 + read-only + + + DBW + Dither Blue Width + 4 + 3 + read-only + + + LTDCEN + LCD-TFT controller enable + bit + 0 + 1 + read-write + + + + + SRCR + SRCR + Shadow Reload Configuration + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + VBR + Vertical Blanking Reload + 1 + 1 + + + IMR + Immediate Reload + 0 + 1 + + + + + BCCR + BCCR + Background Color Configuration + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BC + Background Color Red value + 0 + 24 + + + + + IER + IER + Interrupt Enable Register + 0x34 + 0x20 + read-write + 0x00000000 + + + RRIE + Register Reload interrupt + enable + 3 + 1 + + + TERRIE + Transfer Error Interrupt + Enable + 2 + 1 + + + FUIE + FIFO Underrun Interrupt + Enable + 1 + 1 + + + LIE + Line Interrupt Enable + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x38 + 0x20 + read-only + 0x00000000 + + + RRIF + Register Reload Interrupt + Flag + 3 + 1 + + + TERRIF + Transfer Error interrupt + flag + 2 + 1 + + + FUIF + FIFO Underrun Interrupt + flag + 1 + 1 + + + LIF + Line Interrupt flag + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x3C + 0x20 + write-only + 0x00000000 + + + CRRIF + Clears Register Reload Interrupt + Flag + 3 + 1 + + + CTERRIF + Clears the Transfer Error Interrupt + Flag + 2 + 1 + + + CFUIF + Clears the FIFO Underrun Interrupt + flag + 1 + 1 + + + CLIF + Clears the Line Interrupt + Flag + 0 + 1 + + + + + LIPCR + LIPCR + Line Interrupt Position Configuration + Register + 0x40 + 0x20 + read-write + 0x00000000 + + + LIPOS + Line Interrupt Position + 0 + 11 + + + + + CPSR + CPSR + Current Position Status + Register + 0x44 + 0x20 + read-only + 0x00000000 + + + CXPOS + Current X Position + 16 + 16 + + + CYPOS + Current Y Position + 0 + 16 + + + + + CDSR + CDSR + Current Display Status + Register + 0x48 + 0x20 + read-only + 0x0000000F + + + HSYNCS + Horizontal Synchronization display + Status + 3 + 1 + + + VSYNCS + Vertical Synchronization display + Status + 2 + 1 + + + HDES + Horizontal Data Enable display + Status + 1 + 1 + + + VDES + Vertical Data Enable display + Status + 0 + 1 + + + + + L1CR + L1CR + Layerx Control Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L1WHPCR + L1WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x88 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L1WVPCR + L1WVPCR + Layerx Window Vertical Position + Configuration Register + 0x8C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L1CKCR + L1CKCR + Layerx Color Keying Configuration + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L1PFCR + L1PFCR + Layerx Pixel Format Configuration + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L1CACR + L1CACR + Layerx Constant Alpha Configuration + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L1DCCR + L1DCCR + Layerx Default Color Configuration + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L1BFCR + L1BFCR + Layerx Blending Factors Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L1CFBAR + L1CFBAR + Layerx Color Frame Buffer Address + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L1CFBLR + L1CFBLR + Layerx Color Frame Buffer Length + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L1CFBLNR + L1CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L1CLUTWR + L1CLUTWR + Layerx CLUT Write Register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + L2CR + L2CR + Layerx Control Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L2WHPCR + L2WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x108 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L2WVPCR + L2WVPCR + Layerx Window Vertical Position + Configuration Register + 0x10C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L2CKCR + L2CKCR + Layerx Color Keying Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 15 + 9 + + + CKGREEN + Color Key Green value + 8 + 7 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L2PFCR + L2PFCR + Layerx Pixel Format Configuration + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L2CACR + L2CACR + Layerx Constant Alpha Configuration + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L2DCCR + L2DCCR + Layerx Default Color Configuration + Register + 0x11C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L2BFCR + L2BFCR + Layerx Blending Factors Configuration + Register + 0x120 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L2CFBAR + L2CFBAR + Layerx Color Frame Buffer Address + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L2CFBLR + L2CFBLR + Layerx Color Frame Buffer Length + Register + 0x130 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L2CFBLNR + L2CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0x134 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L2CLUTWR + L2CLUTWR + Layerx CLUT Write Register + 0x144 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + + + HASH + Hash processor + HASH + 0x50060400 + + 0x0 + 0x400 + registers + + + HASH_RNG + Hash and Rng global interrupt + 80 + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + INIT + Initialize message digest + calculation + 2 + 1 + write-only + + + DMAE + DMA enable + 3 + 1 + read-write + + + DATATYPE + Data type selection + 4 + 2 + read-write + + + MODE + Mode selection + 6 + 1 + read-write + + + ALGO0 + Algorithm selection + 7 + 1 + read-write + + + NBW + Number of words already + pushed + 8 + 4 + read-only + + + DINNE + DIN not empty + 12 + 1 + read-only + + + MDMAT + Multiple DMA Transfers + 13 + 1 + read-write + + + LKEY + Long key selection + 16 + 1 + read-write + + + ALGO1 + ALGO + 18 + 1 + read-write + + + + + DIN + DIN + data input register + 0x4 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + STR + STR + start register + 0x8 + 0x20 + 0x00000000 + + + DCAL + Digest calculation + 8 + 1 + write-only + + + NBLW + Number of valid bits in the last word of + the message + 0 + 5 + read-write + + + + + HR0 + HR0 + digest registers + 0xC + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HR1 + HR1 + digest registers + 0x10 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HR2 + HR2 + digest registers + 0x14 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HR3 + HR3 + digest registers + 0x18 + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HR4 + HR4 + digest registers + 0x1C + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + IMR + IMR + interrupt enable register + 0x20 + 0x20 + read-write + 0x00000000 + + + DCIE + Digest calculation completion interrupt + enable + 1 + 1 + + + DINIE + Data input interrupt + enable + 0 + 1 + + + + + SR + SR + status register + 0x24 + 0x20 + 0x00000001 + + + BUSY + Busy bit + 3 + 1 + read-only + + + DMAS + DMA Status + 2 + 1 + read-only + + + DCIS + Digest calculation completion interrupt + status + 1 + 1 + read-write + + + DINIS + Data input interrupt + status + 0 + 1 + read-write + + + + + CSR0 + CSR0 + context swap registers + 0xF8 + 0x20 + read-write + 0x00000000 + + + CSR0 + CSR0 + 0 + 32 + + + + + CSR1 + CSR1 + context swap registers + 0xFC + 0x20 + read-write + 0x00000000 + + + CSR1 + CSR1 + 0 + 32 + + + + + CSR2 + CSR2 + context swap registers + 0x100 + 0x20 + read-write + 0x00000000 + + + CSR2 + CSR2 + 0 + 32 + + + + + CSR3 + CSR3 + context swap registers + 0x104 + 0x20 + read-write + 0x00000000 + + + CSR3 + CSR3 + 0 + 32 + + + + + CSR4 + CSR4 + context swap registers + 0x108 + 0x20 + read-write + 0x00000000 + + + CSR4 + CSR4 + 0 + 32 + + + + + CSR5 + CSR5 + context swap registers + 0x10C + 0x20 + read-write + 0x00000000 + + + CSR5 + CSR5 + 0 + 32 + + + + + CSR6 + CSR6 + context swap registers + 0x110 + 0x20 + read-write + 0x00000000 + + + CSR6 + CSR6 + 0 + 32 + + + + + CSR7 + CSR7 + context swap registers + 0x114 + 0x20 + read-write + 0x00000000 + + + CSR7 + CSR7 + 0 + 32 + + + + + CSR8 + CSR8 + context swap registers + 0x118 + 0x20 + read-write + 0x00000000 + + + CSR8 + CSR8 + 0 + 32 + + + + + CSR9 + CSR9 + context swap registers + 0x11C + 0x20 + read-write + 0x00000000 + + + CSR9 + CSR9 + 0 + 32 + + + + + CSR10 + CSR10 + context swap registers + 0x120 + 0x20 + read-write + 0x00000000 + + + CSR10 + CSR10 + 0 + 32 + + + + + CSR11 + CSR11 + context swap registers + 0x124 + 0x20 + read-write + 0x00000000 + + + CSR11 + CSR11 + 0 + 32 + + + + + CSR12 + CSR12 + context swap registers + 0x128 + 0x20 + read-write + 0x00000000 + + + CSR12 + CSR12 + 0 + 32 + + + + + CSR13 + CSR13 + context swap registers + 0x12C + 0x20 + read-write + 0x00000000 + + + CSR13 + CSR13 + 0 + 32 + + + + + CSR14 + CSR14 + context swap registers + 0x130 + 0x20 + read-write + 0x00000000 + + + CSR14 + CSR14 + 0 + 32 + + + + + CSR15 + CSR15 + context swap registers + 0x134 + 0x20 + read-write + 0x00000000 + + + CSR15 + CSR15 + 0 + 32 + + + + + CSR16 + CSR16 + context swap registers + 0x138 + 0x20 + read-write + 0x00000000 + + + CSR16 + CSR16 + 0 + 32 + + + + + CSR17 + CSR17 + context swap registers + 0x13C + 0x20 + read-write + 0x00000000 + + + CSR17 + CSR17 + 0 + 32 + + + + + CSR18 + CSR18 + context swap registers + 0x140 + 0x20 + read-write + 0x00000000 + + + CSR18 + CSR18 + 0 + 32 + + + + + CSR19 + CSR19 + context swap registers + 0x144 + 0x20 + read-write + 0x00000000 + + + CSR19 + CSR19 + 0 + 32 + + + + + CSR20 + CSR20 + context swap registers + 0x148 + 0x20 + read-write + 0x00000000 + + + CSR20 + CSR20 + 0 + 32 + + + + + CSR21 + CSR21 + context swap registers + 0x14C + 0x20 + read-write + 0x00000000 + + + CSR21 + CSR21 + 0 + 32 + + + + + CSR22 + CSR22 + context swap registers + 0x150 + 0x20 + read-write + 0x00000000 + + + CSR22 + CSR22 + 0 + 32 + + + + + CSR23 + CSR23 + context swap registers + 0x154 + 0x20 + read-write + 0x00000000 + + + CSR23 + CSR23 + 0 + 32 + + + + + CSR24 + CSR24 + context swap registers + 0x158 + 0x20 + read-write + 0x00000000 + + + CSR24 + CSR24 + 0 + 32 + + + + + CSR25 + CSR25 + context swap registers + 0x15C + 0x20 + read-write + 0x00000000 + + + CSR25 + CSR25 + 0 + 32 + + + + + CSR26 + CSR26 + context swap registers + 0x160 + 0x20 + read-write + 0x00000000 + + + CSR26 + CSR26 + 0 + 32 + + + + + CSR27 + CSR27 + context swap registers + 0x164 + 0x20 + read-write + 0x00000000 + + + CSR27 + CSR27 + 0 + 32 + + + + + CSR28 + CSR28 + context swap registers + 0x168 + 0x20 + read-write + 0x00000000 + + + CSR28 + CSR28 + 0 + 32 + + + + + CSR29 + CSR29 + context swap registers + 0x16C + 0x20 + read-write + 0x00000000 + + + CSR29 + CSR29 + 0 + 32 + + + + + CSR30 + CSR30 + context swap registers + 0x170 + 0x20 + read-write + 0x00000000 + + + CSR30 + CSR30 + 0 + 32 + + + + + CSR31 + CSR31 + context swap registers + 0x174 + 0x20 + read-write + 0x00000000 + + + CSR31 + CSR31 + 0 + 32 + + + + + CSR32 + CSR32 + context swap registers + 0x178 + 0x20 + read-write + 0x00000000 + + + CSR32 + CSR32 + 0 + 32 + + + + + CSR33 + CSR33 + context swap registers + 0x17C + 0x20 + read-write + 0x00000000 + + + CSR33 + CSR33 + 0 + 32 + + + + + CSR34 + CSR34 + context swap registers + 0x180 + 0x20 + read-write + 0x00000000 + + + CSR34 + CSR34 + 0 + 32 + + + + + CSR35 + CSR35 + context swap registers + 0x184 + 0x20 + read-write + 0x00000000 + + + CSR35 + CSR35 + 0 + 32 + + + + + CSR36 + CSR36 + context swap registers + 0x188 + 0x20 + read-write + 0x00000000 + + + CSR36 + CSR36 + 0 + 32 + + + + + CSR37 + CSR37 + context swap registers + 0x18C + 0x20 + read-write + 0x00000000 + + + CSR37 + CSR37 + 0 + 32 + + + + + CSR38 + CSR38 + context swap registers + 0x190 + 0x20 + read-write + 0x00000000 + + + CSR38 + CSR38 + 0 + 32 + + + + + CSR39 + CSR39 + context swap registers + 0x194 + 0x20 + read-write + 0x00000000 + + + CSR39 + CSR39 + 0 + 32 + + + + + CSR40 + CSR40 + context swap registers + 0x198 + 0x20 + read-write + 0x00000000 + + + CSR40 + CSR40 + 0 + 32 + + + + + CSR41 + CSR41 + context swap registers + 0x19C + 0x20 + read-write + 0x00000000 + + + CSR41 + CSR41 + 0 + 32 + + + + + CSR42 + CSR42 + context swap registers + 0x1A0 + 0x20 + read-write + 0x00000000 + + + CSR42 + CSR42 + 0 + 32 + + + + + CSR43 + CSR43 + context swap registers + 0x1A4 + 0x20 + read-write + 0x00000000 + + + CSR43 + CSR43 + 0 + 32 + + + + + CSR44 + CSR44 + context swap registers + 0x1A8 + 0x20 + read-write + 0x00000000 + + + CSR44 + CSR44 + 0 + 32 + + + + + CSR45 + CSR45 + context swap registers + 0x1AC + 0x20 + read-write + 0x00000000 + + + CSR45 + CSR45 + 0 + 32 + + + + + CSR46 + CSR46 + context swap registers + 0x1B0 + 0x20 + read-write + 0x00000000 + + + CSR46 + CSR46 + 0 + 32 + + + + + CSR47 + CSR47 + context swap registers + 0x1B4 + 0x20 + read-write + 0x00000000 + + + CSR47 + CSR47 + 0 + 32 + + + + + CSR48 + CSR48 + context swap registers + 0x1B8 + 0x20 + read-write + 0x00000000 + + + CSR48 + CSR48 + 0 + 32 + + + + + CSR49 + CSR49 + context swap registers + 0x1BC + 0x20 + read-write + 0x00000000 + + + CSR49 + CSR49 + 0 + 32 + + + + + CSR50 + CSR50 + context swap registers + 0x1C0 + 0x20 + read-write + 0x00000000 + + + CSR50 + CSR50 + 0 + 32 + + + + + CSR51 + CSR51 + context swap registers + 0x1C4 + 0x20 + read-write + 0x00000000 + + + CSR51 + CSR51 + 0 + 32 + + + + + CSR52 + CSR52 + context swap registers + 0x1C8 + 0x20 + read-write + 0x00000000 + + + CSR52 + CSR52 + 0 + 32 + + + + + CSR53 + CSR53 + context swap registers + 0x1CC + 0x20 + read-write + 0x00000000 + + + CSR53 + CSR53 + 0 + 32 + + + + + HASH_HR0 + HASH_HR0 + HASH digest register + 0x310 + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HASH_HR1 + HASH_HR1 + read-only + 0x314 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HASH_HR2 + HASH_HR2 + read-only + 0x318 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HASH_HR3 + HASH_HR3 + read-only + 0x31C + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HASH_HR4 + HASH_HR4 + read-only + 0x320 + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + HASH_HR5 + HASH_HR5 + read-only + 0x324 + 0x20 + read-only + 0x00000000 + + + H5 + H5 + 0 + 32 + + + + + HASH_HR6 + HASH_HR6 + read-only + 0x328 + 0x20 + read-only + 0x00000000 + + + H6 + H6 + 0 + 32 + + + + + HASH_HR7 + HASH_HR7 + read-only + 0x32C + 0x20 + read-only + 0x00000000 + + + H7 + H7 + 0 + 32 + + + + + + + CRYP + Cryptographic processor + CRYP + 0x50060000 + + 0x0 + 0x400 + registers + + + CRYP + CRYP crypto global interrupt + 79 + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + ALGODIR + Algorithm direction + 2 + 1 + read-write + + + ALGOMODE0 + Algorithm mode + 3 + 3 + read-write + + + DATATYPE + Data type selection + 6 + 2 + read-write + + + KEYSIZE + Key size selection (AES mode + only) + 8 + 2 + read-write + + + FFLUSH + FIFO flush + 14 + 1 + write-only + + + CRYPEN + Cryptographic processor + enable + 15 + 1 + read-write + + + GCM_CCMPH + GCM_CCMPH + 16 + 2 + read-write + + + ALGOMODE3 + ALGOMODE + 19 + 1 + read-write + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x00000003 + + + BUSY + Busy bit + 4 + 1 + + + OFFU + Output FIFO full + 3 + 1 + + + OFNE + Output FIFO not empty + 2 + 1 + + + IFNF + Input FIFO not full + 1 + 1 + + + IFEM + Input FIFO empty + 0 + 1 + + + + + DIN + DIN + data input register + 0x8 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + DOUT + DOUT + data output register + 0xC + 0x20 + read-only + 0x00000000 + + + DATAOUT + Data output + 0 + 32 + + + + + DMACR + DMACR + DMA control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DOEN + DMA output enable + 1 + 1 + + + DIEN + DMA input enable + 0 + 1 + + + + + IMSCR + IMSCR + interrupt mask set/clear + register + 0x14 + 0x20 + read-write + 0x00000000 + + + OUTIM + Output FIFO service interrupt + mask + 1 + 1 + + + INIM + Input FIFO service interrupt + mask + 0 + 1 + + + + + RISR + RISR + raw interrupt status register + 0x18 + 0x20 + read-only + 0x00000001 + + + OUTRIS + Output FIFO service raw interrupt + status + 1 + 1 + + + INRIS + Input FIFO service raw interrupt + status + 0 + 1 + + + + + MISR + MISR + masked interrupt status + register + 0x1C + 0x20 + read-only + 0x00000000 + + + OUTMIS + Output FIFO service masked interrupt + status + 1 + 1 + + + INMIS + Input FIFO service masked interrupt + status + 0 + 1 + + + + + K0LR + K0LR + key registers + 0x20 + 0x20 + write-only + 0x00000000 + + + b224 + b224 + 0 + 1 + + + b225 + b225 + 1 + 1 + + + b226 + b226 + 2 + 1 + + + b227 + b227 + 3 + 1 + + + b228 + b228 + 4 + 1 + + + b229 + b229 + 5 + 1 + + + b230 + b230 + 6 + 1 + + + b231 + b231 + 7 + 1 + + + b232 + b232 + 8 + 1 + + + b233 + b233 + 9 + 1 + + + b234 + b234 + 10 + 1 + + + b235 + b235 + 11 + 1 + + + b236 + b236 + 12 + 1 + + + b237 + b237 + 13 + 1 + + + b238 + b238 + 14 + 1 + + + b239 + b239 + 15 + 1 + + + b240 + b240 + 16 + 1 + + + b241 + b241 + 17 + 1 + + + b242 + b242 + 18 + 1 + + + b243 + b243 + 19 + 1 + + + b244 + b244 + 20 + 1 + + + b245 + b245 + 21 + 1 + + + b246 + b246 + 22 + 1 + + + b247 + b247 + 23 + 1 + + + b248 + b248 + 24 + 1 + + + b249 + b249 + 25 + 1 + + + b250 + b250 + 26 + 1 + + + b251 + b251 + 27 + 1 + + + b252 + b252 + 28 + 1 + + + b253 + b253 + 29 + 1 + + + b254 + b254 + 30 + 1 + + + b255 + b255 + 31 + 1 + + + + + K0RR + K0RR + key registers + 0x24 + 0x20 + write-only + 0x00000000 + + + b192 + b192 + 0 + 1 + + + b193 + b193 + 1 + 1 + + + b194 + b194 + 2 + 1 + + + b195 + b195 + 3 + 1 + + + b196 + b196 + 4 + 1 + + + b197 + b197 + 5 + 1 + + + b198 + b198 + 6 + 1 + + + b199 + b199 + 7 + 1 + + + b200 + b200 + 8 + 1 + + + b201 + b201 + 9 + 1 + + + b202 + b202 + 10 + 1 + + + b203 + b203 + 11 + 1 + + + b204 + b204 + 12 + 1 + + + b205 + b205 + 13 + 1 + + + b206 + b206 + 14 + 1 + + + b207 + b207 + 15 + 1 + + + b208 + b208 + 16 + 1 + + + b209 + b209 + 17 + 1 + + + b210 + b210 + 18 + 1 + + + b211 + b211 + 19 + 1 + + + b212 + b212 + 20 + 1 + + + b213 + b213 + 21 + 1 + + + b214 + b214 + 22 + 1 + + + b215 + b215 + 23 + 1 + + + b216 + b216 + 24 + 1 + + + b217 + b217 + 25 + 1 + + + b218 + b218 + 26 + 1 + + + b219 + b219 + 27 + 1 + + + b220 + b220 + 28 + 1 + + + b221 + b221 + 29 + 1 + + + b222 + b222 + 30 + 1 + + + b223 + b223 + 31 + 1 + + + + + K1LR + K1LR + key registers + 0x28 + 0x20 + write-only + 0x00000000 + + + b160 + b160 + 0 + 1 + + + b161 + b161 + 1 + 1 + + + b162 + b162 + 2 + 1 + + + b163 + b163 + 3 + 1 + + + b164 + b164 + 4 + 1 + + + b165 + b165 + 5 + 1 + + + b166 + b166 + 6 + 1 + + + b167 + b167 + 7 + 1 + + + b168 + b168 + 8 + 1 + + + b169 + b169 + 9 + 1 + + + b170 + b170 + 10 + 1 + + + b171 + b171 + 11 + 1 + + + b172 + b172 + 12 + 1 + + + b173 + b173 + 13 + 1 + + + b174 + b174 + 14 + 1 + + + b175 + b175 + 15 + 1 + + + b176 + b176 + 16 + 1 + + + b177 + b177 + 17 + 1 + + + b178 + b178 + 18 + 1 + + + b179 + b179 + 19 + 1 + + + b180 + b180 + 20 + 1 + + + b181 + b181 + 21 + 1 + + + b182 + b182 + 22 + 1 + + + b183 + b183 + 23 + 1 + + + b184 + b184 + 24 + 1 + + + b185 + b185 + 25 + 1 + + + b186 + b186 + 26 + 1 + + + b187 + b187 + 27 + 1 + + + b188 + b188 + 28 + 1 + + + b189 + b189 + 29 + 1 + + + b190 + b190 + 30 + 1 + + + b191 + b191 + 31 + 1 + + + + + K1RR + K1RR + key registers + 0x2C + 0x20 + write-only + 0x00000000 + + + b128 + b128 + 0 + 1 + + + b129 + b129 + 1 + 1 + + + b130 + b130 + 2 + 1 + + + b131 + b131 + 3 + 1 + + + b132 + b132 + 4 + 1 + + + b133 + b133 + 5 + 1 + + + b134 + b134 + 6 + 1 + + + b135 + b135 + 7 + 1 + + + b136 + b136 + 8 + 1 + + + b137 + b137 + 9 + 1 + + + b138 + b138 + 10 + 1 + + + b139 + b139 + 11 + 1 + + + b140 + b140 + 12 + 1 + + + b141 + b141 + 13 + 1 + + + b142 + b142 + 14 + 1 + + + b143 + b143 + 15 + 1 + + + b144 + b144 + 16 + 1 + + + b145 + b145 + 17 + 1 + + + b146 + b146 + 18 + 1 + + + b147 + b147 + 19 + 1 + + + b148 + b148 + 20 + 1 + + + b149 + b149 + 21 + 1 + + + b150 + b150 + 22 + 1 + + + b151 + b151 + 23 + 1 + + + b152 + b152 + 24 + 1 + + + b153 + b153 + 25 + 1 + + + b154 + b154 + 26 + 1 + + + b155 + b155 + 27 + 1 + + + b156 + b156 + 28 + 1 + + + b157 + b157 + 29 + 1 + + + b158 + b158 + 30 + 1 + + + b159 + b159 + 31 + 1 + + + + + K2LR + K2LR + key registers + 0x30 + 0x20 + write-only + 0x00000000 + + + b96 + b96 + 0 + 1 + + + b97 + b97 + 1 + 1 + + + b98 + b98 + 2 + 1 + + + b99 + b99 + 3 + 1 + + + b100 + b100 + 4 + 1 + + + b101 + b101 + 5 + 1 + + + b102 + b102 + 6 + 1 + + + b103 + b103 + 7 + 1 + + + b104 + b104 + 8 + 1 + + + b105 + b105 + 9 + 1 + + + b106 + b106 + 10 + 1 + + + b107 + b107 + 11 + 1 + + + b108 + b108 + 12 + 1 + + + b109 + b109 + 13 + 1 + + + b110 + b110 + 14 + 1 + + + b111 + b111 + 15 + 1 + + + b112 + b112 + 16 + 1 + + + b113 + b113 + 17 + 1 + + + b114 + b114 + 18 + 1 + + + b115 + b115 + 19 + 1 + + + b116 + b116 + 20 + 1 + + + b117 + b117 + 21 + 1 + + + b118 + b118 + 22 + 1 + + + b119 + b119 + 23 + 1 + + + b120 + b120 + 24 + 1 + + + b121 + b121 + 25 + 1 + + + b122 + b122 + 26 + 1 + + + b123 + b123 + 27 + 1 + + + b124 + b124 + 28 + 1 + + + b125 + b125 + 29 + 1 + + + b126 + b126 + 30 + 1 + + + b127 + b127 + 31 + 1 + + + + + K2RR + K2RR + key registers + 0x34 + 0x20 + write-only + 0x00000000 + + + b64 + b64 + 0 + 1 + + + b65 + b65 + 1 + 1 + + + b66 + b66 + 2 + 1 + + + b67 + b67 + 3 + 1 + + + b68 + b68 + 4 + 1 + + + b69 + b69 + 5 + 1 + + + b70 + b70 + 6 + 1 + + + b71 + b71 + 7 + 1 + + + b72 + b72 + 8 + 1 + + + b73 + b73 + 9 + 1 + + + b74 + b74 + 10 + 1 + + + b75 + b75 + 11 + 1 + + + b76 + b76 + 12 + 1 + + + b77 + b77 + 13 + 1 + + + b78 + b78 + 14 + 1 + + + b79 + b79 + 15 + 1 + + + b80 + b80 + 16 + 1 + + + b81 + b81 + 17 + 1 + + + b82 + b82 + 18 + 1 + + + b83 + b83 + 19 + 1 + + + b84 + b84 + 20 + 1 + + + b85 + b85 + 21 + 1 + + + b86 + b86 + 22 + 1 + + + b87 + b87 + 23 + 1 + + + b88 + b88 + 24 + 1 + + + b89 + b89 + 25 + 1 + + + b90 + b90 + 26 + 1 + + + b91 + b91 + 27 + 1 + + + b92 + b92 + 28 + 1 + + + b93 + b93 + 29 + 1 + + + b94 + b94 + 30 + 1 + + + b95 + b95 + 31 + 1 + + + + + K3LR + K3LR + key registers + 0x38 + 0x20 + write-only + 0x00000000 + + + b32 + b32 + 0 + 1 + + + b33 + b33 + 1 + 1 + + + b34 + b34 + 2 + 1 + + + b35 + b35 + 3 + 1 + + + b36 + b36 + 4 + 1 + + + b37 + b37 + 5 + 1 + + + b38 + b38 + 6 + 1 + + + b39 + b39 + 7 + 1 + + + b40 + b40 + 8 + 1 + + + b41 + b41 + 9 + 1 + + + b42 + b42 + 10 + 1 + + + b43 + b43 + 11 + 1 + + + b44 + b44 + 12 + 1 + + + b45 + b45 + 13 + 1 + + + b46 + b46 + 14 + 1 + + + b47 + b47 + 15 + 1 + + + b48 + b48 + 16 + 1 + + + b49 + b49 + 17 + 1 + + + b50 + b50 + 18 + 1 + + + b51 + b51 + 19 + 1 + + + b52 + b52 + 20 + 1 + + + b53 + b53 + 21 + 1 + + + b54 + b54 + 22 + 1 + + + b55 + b55 + 23 + 1 + + + b56 + b56 + 24 + 1 + + + b57 + b57 + 25 + 1 + + + b58 + b58 + 26 + 1 + + + b59 + b59 + 27 + 1 + + + b60 + b60 + 28 + 1 + + + b61 + b61 + 29 + 1 + + + b62 + b62 + 30 + 1 + + + b63 + b63 + 31 + 1 + + + + + K3RR + K3RR + key registers + 0x3C + 0x20 + write-only + 0x00000000 + + + b0 + b0 + 0 + 1 + + + b1 + b1 + 1 + 1 + + + b2 + b2 + 2 + 1 + + + b3 + b3 + 3 + 1 + + + b4 + b4 + 4 + 1 + + + b5 + b5 + 5 + 1 + + + b6 + b6 + 6 + 1 + + + b7 + b7 + 7 + 1 + + + b8 + b8 + 8 + 1 + + + b9 + b9 + 9 + 1 + + + b10 + b10 + 10 + 1 + + + b11 + b11 + 11 + 1 + + + b12 + b12 + 12 + 1 + + + b13 + b13 + 13 + 1 + + + b14 + b14 + 14 + 1 + + + b15 + b15 + 15 + 1 + + + b16 + b16 + 16 + 1 + + + b17 + b17 + 17 + 1 + + + b18 + b18 + 18 + 1 + + + b19 + b19 + 19 + 1 + + + b20 + b20 + 20 + 1 + + + b21 + b21 + 21 + 1 + + + b22 + b22 + 22 + 1 + + + b23 + b23 + 23 + 1 + + + b24 + b24 + 24 + 1 + + + b25 + b25 + 25 + 1 + + + b26 + b26 + 26 + 1 + + + b27 + b27 + 27 + 1 + + + b28 + b28 + 28 + 1 + + + b29 + b29 + 29 + 1 + + + b30 + b30 + 30 + 1 + + + b31 + b31 + 31 + 1 + + + + + IV0LR + IV0LR + initialization vector + registers + 0x40 + 0x20 + read-write + 0x00000000 + + + IV31 + IV31 + 0 + 1 + + + IV30 + IV30 + 1 + 1 + + + IV29 + IV29 + 2 + 1 + + + IV28 + IV28 + 3 + 1 + + + IV27 + IV27 + 4 + 1 + + + IV26 + IV26 + 5 + 1 + + + IV25 + IV25 + 6 + 1 + + + IV24 + IV24 + 7 + 1 + + + IV23 + IV23 + 8 + 1 + + + IV22 + IV22 + 9 + 1 + + + IV21 + IV21 + 10 + 1 + + + IV20 + IV20 + 11 + 1 + + + IV19 + IV19 + 12 + 1 + + + IV18 + IV18 + 13 + 1 + + + IV17 + IV17 + 14 + 1 + + + IV16 + IV16 + 15 + 1 + + + IV15 + IV15 + 16 + 1 + + + IV14 + IV14 + 17 + 1 + + + IV13 + IV13 + 18 + 1 + + + IV12 + IV12 + 19 + 1 + + + IV11 + IV11 + 20 + 1 + + + IV10 + IV10 + 21 + 1 + + + IV9 + IV9 + 22 + 1 + + + IV8 + IV8 + 23 + 1 + + + IV7 + IV7 + 24 + 1 + + + IV6 + IV6 + 25 + 1 + + + IV5 + IV5 + 26 + 1 + + + IV4 + IV4 + 27 + 1 + + + IV3 + IV3 + 28 + 1 + + + IV2 + IV2 + 29 + 1 + + + IV1 + IV1 + 30 + 1 + + + IV0 + IV0 + 31 + 1 + + + + + IV0RR + IV0RR + initialization vector + registers + 0x44 + 0x20 + read-write + 0x00000000 + + + IV63 + IV63 + 0 + 1 + + + IV62 + IV62 + 1 + 1 + + + IV61 + IV61 + 2 + 1 + + + IV60 + IV60 + 3 + 1 + + + IV59 + IV59 + 4 + 1 + + + IV58 + IV58 + 5 + 1 + + + IV57 + IV57 + 6 + 1 + + + IV56 + IV56 + 7 + 1 + + + IV55 + IV55 + 8 + 1 + + + IV54 + IV54 + 9 + 1 + + + IV53 + IV53 + 10 + 1 + + + IV52 + IV52 + 11 + 1 + + + IV51 + IV51 + 12 + 1 + + + IV50 + IV50 + 13 + 1 + + + IV49 + IV49 + 14 + 1 + + + IV48 + IV48 + 15 + 1 + + + IV47 + IV47 + 16 + 1 + + + IV46 + IV46 + 17 + 1 + + + IV45 + IV45 + 18 + 1 + + + IV44 + IV44 + 19 + 1 + + + IV43 + IV43 + 20 + 1 + + + IV42 + IV42 + 21 + 1 + + + IV41 + IV41 + 22 + 1 + + + IV40 + IV40 + 23 + 1 + + + IV39 + IV39 + 24 + 1 + + + IV38 + IV38 + 25 + 1 + + + IV37 + IV37 + 26 + 1 + + + IV36 + IV36 + 27 + 1 + + + IV35 + IV35 + 28 + 1 + + + IV34 + IV34 + 29 + 1 + + + IV33 + IV33 + 30 + 1 + + + IV32 + IV32 + 31 + 1 + + + + + IV1LR + IV1LR + initialization vector + registers + 0x48 + 0x20 + read-write + 0x00000000 + + + IV95 + IV95 + 0 + 1 + + + IV94 + IV94 + 1 + 1 + + + IV93 + IV93 + 2 + 1 + + + IV92 + IV92 + 3 + 1 + + + IV91 + IV91 + 4 + 1 + + + IV90 + IV90 + 5 + 1 + + + IV89 + IV89 + 6 + 1 + + + IV88 + IV88 + 7 + 1 + + + IV87 + IV87 + 8 + 1 + + + IV86 + IV86 + 9 + 1 + + + IV85 + IV85 + 10 + 1 + + + IV84 + IV84 + 11 + 1 + + + IV83 + IV83 + 12 + 1 + + + IV82 + IV82 + 13 + 1 + + + IV81 + IV81 + 14 + 1 + + + IV80 + IV80 + 15 + 1 + + + IV79 + IV79 + 16 + 1 + + + IV78 + IV78 + 17 + 1 + + + IV77 + IV77 + 18 + 1 + + + IV76 + IV76 + 19 + 1 + + + IV75 + IV75 + 20 + 1 + + + IV74 + IV74 + 21 + 1 + + + IV73 + IV73 + 22 + 1 + + + IV72 + IV72 + 23 + 1 + + + IV71 + IV71 + 24 + 1 + + + IV70 + IV70 + 25 + 1 + + + IV69 + IV69 + 26 + 1 + + + IV68 + IV68 + 27 + 1 + + + IV67 + IV67 + 28 + 1 + + + IV66 + IV66 + 29 + 1 + + + IV65 + IV65 + 30 + 1 + + + IV64 + IV64 + 31 + 1 + + + + + IV1RR + IV1RR + initialization vector + registers + 0x4C + 0x20 + read-write + 0x00000000 + + + IV127 + IV127 + 0 + 1 + + + IV126 + IV126 + 1 + 1 + + + IV125 + IV125 + 2 + 1 + + + IV124 + IV124 + 3 + 1 + + + IV123 + IV123 + 4 + 1 + + + IV122 + IV122 + 5 + 1 + + + IV121 + IV121 + 6 + 1 + + + IV120 + IV120 + 7 + 1 + + + IV119 + IV119 + 8 + 1 + + + IV118 + IV118 + 9 + 1 + + + IV117 + IV117 + 10 + 1 + + + IV116 + IV116 + 11 + 1 + + + IV115 + IV115 + 12 + 1 + + + IV114 + IV114 + 13 + 1 + + + IV113 + IV113 + 14 + 1 + + + IV112 + IV112 + 15 + 1 + + + IV111 + IV111 + 16 + 1 + + + IV110 + IV110 + 17 + 1 + + + IV109 + IV109 + 18 + 1 + + + IV108 + IV108 + 19 + 1 + + + IV107 + IV107 + 20 + 1 + + + IV106 + IV106 + 21 + 1 + + + IV105 + IV105 + 22 + 1 + + + IV104 + IV104 + 23 + 1 + + + IV103 + IV103 + 24 + 1 + + + IV102 + IV102 + 25 + 1 + + + IV101 + IV101 + 26 + 1 + + + IV100 + IV100 + 27 + 1 + + + IV99 + IV99 + 28 + 1 + + + IV98 + IV98 + 29 + 1 + + + IV97 + IV97 + 30 + 1 + + + IV96 + IV96 + 31 + 1 + + + + + CSGCMCCM0R + CSGCMCCM0R + context swap register + 0x50 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM0R + CSGCMCCM0R + 0 + 32 + + + + + CSGCMCCM1R + CSGCMCCM1R + context swap register + 0x54 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM1R + CSGCMCCM1R + 0 + 32 + + + + + CSGCMCCM2R + CSGCMCCM2R + context swap register + 0x58 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM2R + CSGCMCCM2R + 0 + 32 + + + + + CSGCMCCM3R + CSGCMCCM3R + context swap register + 0x5C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM3R + CSGCMCCM3R + 0 + 32 + + + + + CSGCMCCM4R + CSGCMCCM4R + context swap register + 0x60 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM4R + CSGCMCCM4R + 0 + 32 + + + + + CSGCMCCM5R + CSGCMCCM5R + context swap register + 0x64 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM5R + CSGCMCCM5R + 0 + 32 + + + + + CSGCMCCM6R + CSGCMCCM6R + context swap register + 0x68 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM6R + CSGCMCCM6R + 0 + 32 + + + + + CSGCMCCM7R + CSGCMCCM7R + context swap register + 0x6C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM7R + CSGCMCCM7R + 0 + 32 + + + + + CSGCM0R + CSGCM0R + context swap register + 0x70 + 0x20 + read-write + 0x00000000 + + + CSGCM0R + CSGCM0R + 0 + 32 + + + + + CSGCM1R + CSGCM1R + context swap register + 0x74 + 0x20 + read-write + 0x00000000 + + + CSGCM1R + CSGCM1R + 0 + 32 + + + + + CSGCM2R + CSGCM2R + context swap register + 0x78 + 0x20 + read-write + 0x00000000 + + + CSGCM2R + CSGCM2R + 0 + 32 + + + + + CSGCM3R + CSGCM3R + context swap register + 0x7C + 0x20 + read-write + 0x00000000 + + + CSGCM3R + CSGCM3R + 0 + 32 + + + + + CSGCM4R + CSGCM4R + context swap register + 0x80 + 0x20 + read-write + 0x00000000 + + + CSGCM4R + CSGCM4R + 0 + 32 + + + + + CSGCM5R + CSGCM5R + context swap register + 0x84 + 0x20 + read-write + 0x00000000 + + + CSGCM5R + CSGCM5R + 0 + 32 + + + + + CSGCM6R + CSGCM6R + context swap register + 0x88 + 0x20 + read-write + 0x00000000 + + + CSGCM6R + CSGCM6R + 0 + 32 + + + + + CSGCM7R + CSGCM7R + context swap register + 0x8C + 0x20 + read-write + 0x00000000 + + + CSGCM7R + CSGCM7R + 0 + 32 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + FPU + Floating point interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CTRL + CTRL + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + LOAD + LOAD + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + VAL + VAL + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + Instruction access violation + flag + 1 + 1 + + + MUNSTKERR + Memory manager fault on unstacking for a + return from exception + 3 + 1 + + + MSTKERR + Memory manager fault on stacking for + exception entry. + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + Memory Management Fault Address Register + (MMAR) valid flag + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + MMFAR + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + BFAR + Bus fault address + 0 + 32 + + + + + AFSR + AFSR + Auxiliary fault status + register + 0x3C + 0x20 + read-write + 0x00000000 + + + IMPDEF + Implementation defined + 0 + 32 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISMCYCINT + DISMCYCINT + 0 + 1 + + + DISDEFWBUF + DISDEFWBUF + 1 + 1 + + + DISFOLD + DISFOLD + 2 + 1 + + + DISFPCA + DISFPCA + 8 + 1 + + + DISOOFP + DISOOFP + 9 + 1 + + + + + + + diff --git a/dev/svd/STM32F411.svd b/dev/svd/STM32F411.svd new file mode 100644 index 00000000000..585602d208c --- /dev/null +++ b/dev/svd/STM32F411.svd @@ -0,0 +1,27110 @@ + + + STM32F411 + 1.1 + STM32F411 + + + CM4 + r1p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + ADC_Common + ADC common registers + ADC + 0x40012300 + + 0x0 + 0x9 + registers + + + FPU + FPU interrupt + 81 + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x51 + registers + + + ADC + ADC1 global interrupt + 18 + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_RTC_Stop + RTC stopped when Core is + halted + 10 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_I2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_I2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_I2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + FLASH global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + 0x00000000 + + + LATENCY + Latency + 0 + 3 + read-write + + + PRFTEN + Prefetch enable + 8 + 1 + read-write + + + ICEN + Instruction cache enable + 9 + 1 + read-write + + + DCEN + Data cache enable + 10 + 1 + read-write + + + ICRST + Instruction cache reset + 11 + 1 + write-only + + + DCRST + Data cache reset + 12 + 1 + read-write + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + PGSERR + Programming sequence error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase + 2 + 1 + + + SNB + Sector number + 3 + 4 + + + PSIZE + Program size + 8 + 2 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x00000014 + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WDG_SW + WDG_SW User option bytes + 5 + 1 + + + nRST_STOP + nRST_STOP User option + bytes + 6 + 1 + + + nRST_STDBY + nRST_STDBY User option + bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 12 + + + + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + FS_DCFG + FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + FS_DCTL + FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + FS_DSTS + FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + FS_DIEPMSK + FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + FS_DOEPMSK + FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + FS_DAINT + FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + FS_DAINTMSK + FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DVBUSDIS + DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + DVBUSPULSE + DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + FS_DIEPCTL0 + FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + DOEPCTL1 + DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPINT0 + DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT1 + DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT2 + DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT3 + DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DOEPINT0 + DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT1 + DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT2 + DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT3 + DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DTXFSTS0 + DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + + FS_GOTGCTL + FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + FS_GOTGINT + FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + FS_GAHBCFG + FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + FS_GUSBCFG + FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + FS_GRSTCTL + FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + FS_GINTSTS + FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + FS_GINTMSK + FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + FS_GRXSTSR_Device + FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXSTSR_Host + FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXFSIZ + FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + FS_GNPTXFSIZ_Device + FS_GNPTXFSIZ_Device + OTG_FS non-periodic transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + FS_GNPTXFSIZ_Host + FS_GNPTXFSIZ_Host + OTG_FS non-periodic transmit FIFO size + register (Host mode) + FS_GNPTXFSIZ_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + FS_GNPTXSTS + FS_GNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + FS_GCCFG + FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + + + FS_CID + FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + FS_HPTXFSIZ + FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF1 + FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF2 + FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF3 + FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + + FS_HCFG + FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + FS_HFNUM + FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + FS_HPTXSTS + FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + FS_HPRT + FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + FS_HCCHAR0 + FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR1 + FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR2 + FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR3 + FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR4 + FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR5 + FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR6 + FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR7 + FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCINT0 + FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT1 + FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT2 + FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT3 + FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT4 + FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT5 + FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT6 + FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT7 + FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINTMSK0 + FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK1 + FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK2 + FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK3 + FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK4 + FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK5 + FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK6 + FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK7 + FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCTSIZ0 + FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ1 + FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ2 + FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ3 + FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ4 + FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ5 + FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ6 + FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ7 + FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + + FS_PCGCCTL + FS_PCGCCTL + OTG_FS power and clock gating control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + + CR + CR + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ADCDC1 + ADCDC1 + 13 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + PLS + PVD level selection + 5 + 3 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + CWUF + Clear wakeup flag + 2 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + LPDS + Low-power deep sleep + 0 + 1 + + + + + CSR + CSR + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUF + Wakeup flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + EWUP + Enable WKUP pin + 8 + 1 + read-write + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + PWRRST + Power interface reset + 28 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM2RST + TIM2 reset + 0 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM11RST + TIM11 reset + 18 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SDIORST + SDIO reset + 11 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + TIM1RST + TIM1 reset + 0 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + PWREN + Power interface clock + enable + 28 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + SDIOEN + SDIO clock enable + 11 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4EN + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + SDIOLPEN + SDIO clock enable during Sleep + mode + 11 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SRx + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SNx + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + COE + Calibration output enable + 23 + 1 + + + OSEL + Output selection + 21 + 2 + + + POL + Output polarity + 20 + 1 + + + COSEL + Calibration Output + selection + 19 + 1 + + + BKP + Backup + 18 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + DCE + Coarse digital calibration + enable + 7 + 1 + + + FMT + Hour format + 6 + 1 + + + BYPSHAD + Bypass the shadow + registers + 5 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + TAMPER2 detection flag + 14 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + CALIBR + CALIBR + calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + DCS + Digital calibration sign + 7 + 1 + + + DC + Digital calibration + 0 + 5 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAFCR + TAFCR + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + SDIO + Secure digital input/output + interface + SDIO + 0x40012C00 + + 0x0 + 0x400 + registers + + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + CE_ATACMD + CE-ATA command + 14 + 1 + + + nIEN + not Interrupt Enable + 13 + 1 + + + ENCMDcompl + Enable CMD completion + 12 + 1 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal). + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + Card Status + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + Card Status + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + Card Status + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + Card Status + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer. + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + CEATAEND + CE-ATA command completion signal + received for CMD61 + 23 + 1 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + STBITERR + Start bit not detected on all data + signals in wide bus mode + 9 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEATAENDC + CEATAEND flag clear bit + 23 + 1 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + STBITERRC + STBITERR flag clear bit + 9 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + CEATAENDIE + CE-ATA command completion signal + received interrupt enable + 23 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + STBITERRIE + Start bit error interrupt + enable + 9 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO. + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + MEM_MODE + 0 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADC1DC2 + ADC1DC2 + 16 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + + + TIM8 + 0x40010400 + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + + + TIM11 + General-purpose-timers + TIM + 0x40014800 + + 0x0 + 0x400 + registers + + + SPI2 + SPI2 global interrupt + 36 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + RMP + Input 1 remapping + capability + 0 + 2 + + + + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + SPI3 + SPI3 global interrupt + 51 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + ITR1_RMP + Timer Input 4 remap + 10 + 2 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + SPI4 + SPI4 global interrupt + 84 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM4 + 0x40000800 + + + TIM5 + General-purpose-timers + TIM + 0x40000C00 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + IT4_RMP + Timer Input 4 remap + 6 + 2 + + + + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011000 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + CTS + CTS flag + 9 + 1 + read-write + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x18 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + + + USART2 + 0x40004400 + + + USART6 + 0x40011400 + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + PVD + PVD through EXTI line detection + interrupt + 1 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + write-only + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + write-only + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTC_Alarm + RTC Alarms (A and B) through EXTI line + interrupt + 41 + + + + GPIOH + General-purpose I/Os + GPIO + 0x40021C00 + + 0x0 + 0x400 + registers + + + SDIO + SDIO global interrupt + 49 + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOE + 0x40021000 + + + GPIOD + 0X40020C00 + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + + GPIOC + 0x40020800 + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + I2C3 + Inter-integrated circuit + I2C + 0x40005C00 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SWRST + Software reset + 15 + 1 + + + ALERT + SMBus alert + 13 + 1 + + + PEC + Packet error checking + 12 + 1 + + + POS + Acknowledge/PEC Position (for data + reception) + 11 + 1 + + + ACK + Acknowledge enable + 10 + 1 + + + STOP + Stop generation + 9 + 1 + + + START + Start generation + 8 + 1 + + + NOSTRETCH + Clock stretching disable (Slave + mode) + 7 + 1 + + + ENGC + General call enable + 6 + 1 + + + ENPEC + PEC enable + 5 + 1 + + + ENARP + ARP enable + 4 + 1 + + + SMBTYPE + SMBus type + 3 + 1 + + + SMBUS + SMBus mode + 1 + 1 + + + PE + Peripheral enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + LAST + DMA last transfer + 12 + 1 + + + DMAEN + DMA requests enable + 11 + 1 + + + ITBUFEN + Buffer interrupt enable + 10 + 1 + + + ITEVTEN + Event interrupt enable + 9 + 1 + + + ITERREN + Error interrupt enable + 8 + 1 + + + FREQ + Peripheral clock frequency + 0 + 6 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + ADDMODE + Addressing mode (slave + mode) + 15 + 1 + + + ADD10 + Interface address + 8 + 2 + + + ADD7 + Interface address + 1 + 7 + + + ADD0 + Interface address + 0 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x0000 + + + ADD2 + Interface address + 1 + 7 + + + ENDUAL + Dual addressing mode + enable + 0 + 1 + + + + + DR + DR + Data register + 0x10 + 0x20 + read-write + 0x0000 + + + DR + 8-bit data register + 0 + 8 + + + + + SR1 + SR1 + Status register 1 + 0x14 + 0x20 + 0x0000 + + + SMBALERT + SMBus alert + 15 + 1 + read-write + + + TIMEOUT + Timeout or Tlow error + 14 + 1 + read-write + + + PECERR + PEC Error in reception + 12 + 1 + read-write + + + OVR + Overrun/Underrun + 11 + 1 + read-write + + + AF + Acknowledge failure + 10 + 1 + read-write + + + ARLO + Arbitration lost (master + mode) + 9 + 1 + read-write + + + BERR + Bus error + 8 + 1 + read-write + + + TxE + Data register empty + (transmitters) + 7 + 1 + read-only + + + RxNE + Data register not empty + (receivers) + 6 + 1 + read-only + + + STOPF + Stop detection (slave + mode) + 4 + 1 + read-only + + + ADD10 + 10-bit header sent (Master + mode) + 3 + 1 + read-only + + + BTF + Byte transfer finished + 2 + 1 + read-only + + + ADDR + Address sent (master mode)/matched + (slave mode) + 1 + 1 + read-only + + + SB + Start bit (Master mode) + 0 + 1 + read-only + + + + + SR2 + SR2 + Status register 2 + 0x18 + 0x20 + read-only + 0x0000 + + + PEC + acket error checking + register + 8 + 8 + + + DUALF + Dual flag (Slave mode) + 7 + 1 + + + SMBHOST + SMBus host header (Slave + mode) + 6 + 1 + + + SMBDEFAULT + SMBus device default address (Slave + mode) + 5 + 1 + + + GENCALL + General call address (Slave + mode) + 4 + 1 + + + TRA + Transmitter/receiver + 2 + 1 + + + BUSY + Bus busy + 1 + 1 + + + MSL + Master/slave + 0 + 1 + + + + + CCR + CCR + Clock control register + 0x1C + 0x20 + read-write + 0x0000 + + + F_S + I2C master mode selection + 15 + 1 + + + DUTY + Fast mode duty cycle + 14 + 1 + + + CCR + Clock control register in Fast/Standard + mode (Master mode) + 0 + 12 + + + + + TRISE + TRISE + TRISE register + 0x20 + 0x20 + read-write + 0x0002 + + + TRISE + Maximum rise time in Fast/Standard mode + (Master mode) + 0 + 6 + + + + + + + I2C2 + 0x40005800 + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + I2C1 + 0x40005400 + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2S2ext + Serial peripheral interface + SPI + 0x40003400 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + DFF + Data frame format + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + FRF + Frame format + 4 + 1 + + + SSOE + SS output enable + 2 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + TIFRFE + TI frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + I2S3ext + 0x40004000 + + + SPI1 + 0x40013000 + + + SPI2 + 0x40003800 + + SPI1 + SPI1 global interrupt + 35 + + + + SPI3 + 0x40003C00 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI4 + 0x40013400 + + SPI3 + SPI3 global interrupt + 51 + + + + SPI5 + 0x40015000 + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x351 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + FPU + Floating point interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CTRL + CTRL + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + LOAD + LOAD + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + VAL + VAL + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + Instruction access violation + flag + 1 + 1 + + + MUNSTKERR + Memory manager fault on unstacking for a + return from exception + 3 + 1 + + + MSTKERR + Memory manager fault on stacking for + exception entry. + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + Memory Management Fault Address Register + (MMAR) valid flag + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + MMFAR + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + BFAR + Bus fault address + 0 + 32 + + + + + AFSR + AFSR + Auxiliary fault status + register + 0x3C + 0x20 + read-write + 0x00000000 + + + IMPDEF + Implementation defined + 0 + 32 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISMCYCINT + DISMCYCINT + 0 + 1 + + + DISDEFWBUF + DISDEFWBUF + 1 + 1 + + + DISFOLD + DISFOLD + 2 + 1 + + + DISFPCA + DISFPCA + 8 + 1 + + + DISOOFP + DISOOFP + 9 + 1 + + + + + + + diff --git a/dev/svd/STM32F427.svd b/dev/svd/STM32F427.svd new file mode 100644 index 00000000000..a99b3831342 --- /dev/null +++ b/dev/svd/STM32F427.svd @@ -0,0 +1,63121 @@ + + + STM32F427 + 1.2 + STM32F427 + + + CM4 + r1p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + RNG + Random number generator + RNG + 0x50060800 + + 0x0 + 0x400 + registers + + + FPU + FPU interrupt + 81 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + IE + Interrupt enable + 3 + 1 + + + RNGEN + Random number generator + enable + 2 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + 0x00000000 + + + SEIS + Seed error interrupt + status + 6 + 1 + read-write + + + CEIS + Clock error interrupt + status + 5 + 1 + read-write + + + SECS + Seed error current status + 2 + 1 + read-only + + + CECS + Clock error current status + 1 + 1 + read-only + + + DRDY + Data ready + 0 + 1 + read-only + + + + + DR + DR + data register + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data + 0 + 32 + + + + + + + HASH + Hash processor + HASH + 0x50060400 + + 0x0 + 0x400 + registers + + + HASH_RNG + Hash and Rng global interrupt + 80 + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + INIT + Initialize message digest + calculation + 2 + 1 + write-only + + + DMAE + DMA enable + 3 + 1 + read-write + + + DATATYPE + Data type selection + 4 + 2 + read-write + + + MODE + Mode selection + 6 + 1 + read-write + + + ALGO0 + Algorithm selection + 7 + 1 + read-write + + + NBW + Number of words already + pushed + 8 + 4 + read-only + + + DINNE + DIN not empty + 12 + 1 + read-only + + + MDMAT + Multiple DMA Transfers + 13 + 1 + read-write + + + LKEY + Long key selection + 16 + 1 + read-write + + + ALGO1 + ALGO + 18 + 1 + read-write + + + + + DIN + DIN + data input register + 0x4 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + STR + STR + start register + 0x8 + 0x20 + 0x00000000 + + + DCAL + Digest calculation + 8 + 1 + write-only + + + NBLW + Number of valid bits in the last word of + the message + 0 + 5 + read-write + + + + + HR0 + HR0 + digest registers + 0xC + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HR1 + HR1 + digest registers + 0x10 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HR2 + HR2 + digest registers + 0x14 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HR3 + HR3 + digest registers + 0x18 + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HR4 + HR4 + digest registers + 0x1C + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + IMR + IMR + interrupt enable register + 0x20 + 0x20 + read-write + 0x00000000 + + + DCIE + Digest calculation completion interrupt + enable + 1 + 1 + + + DINIE + Data input interrupt + enable + 0 + 1 + + + + + SR + SR + status register + 0x24 + 0x20 + 0x00000001 + + + BUSY + Busy bit + 3 + 1 + read-only + + + DMAS + DMA Status + 2 + 1 + read-only + + + DCIS + Digest calculation completion interrupt + status + 1 + 1 + read-write + + + DINIS + Data input interrupt + status + 0 + 1 + read-write + + + + + CSR0 + CSR0 + context swap registers + 0xF8 + 0x20 + read-write + 0x00000000 + + + CSR0 + CSR0 + 0 + 32 + + + + + CSR1 + CSR1 + context swap registers + 0xFC + 0x20 + read-write + 0x00000000 + + + CSR1 + CSR1 + 0 + 32 + + + + + CSR2 + CSR2 + context swap registers + 0x100 + 0x20 + read-write + 0x00000000 + + + CSR2 + CSR2 + 0 + 32 + + + + + CSR3 + CSR3 + context swap registers + 0x104 + 0x20 + read-write + 0x00000000 + + + CSR3 + CSR3 + 0 + 32 + + + + + CSR4 + CSR4 + context swap registers + 0x108 + 0x20 + read-write + 0x00000000 + + + CSR4 + CSR4 + 0 + 32 + + + + + CSR5 + CSR5 + context swap registers + 0x10C + 0x20 + read-write + 0x00000000 + + + CSR5 + CSR5 + 0 + 32 + + + + + CSR6 + CSR6 + context swap registers + 0x110 + 0x20 + read-write + 0x00000000 + + + CSR6 + CSR6 + 0 + 32 + + + + + CSR7 + CSR7 + context swap registers + 0x114 + 0x20 + read-write + 0x00000000 + + + CSR7 + CSR7 + 0 + 32 + + + + + CSR8 + CSR8 + context swap registers + 0x118 + 0x20 + read-write + 0x00000000 + + + CSR8 + CSR8 + 0 + 32 + + + + + CSR9 + CSR9 + context swap registers + 0x11C + 0x20 + read-write + 0x00000000 + + + CSR9 + CSR9 + 0 + 32 + + + + + CSR10 + CSR10 + context swap registers + 0x120 + 0x20 + read-write + 0x00000000 + + + CSR10 + CSR10 + 0 + 32 + + + + + CSR11 + CSR11 + context swap registers + 0x124 + 0x20 + read-write + 0x00000000 + + + CSR11 + CSR11 + 0 + 32 + + + + + CSR12 + CSR12 + context swap registers + 0x128 + 0x20 + read-write + 0x00000000 + + + CSR12 + CSR12 + 0 + 32 + + + + + CSR13 + CSR13 + context swap registers + 0x12C + 0x20 + read-write + 0x00000000 + + + CSR13 + CSR13 + 0 + 32 + + + + + CSR14 + CSR14 + context swap registers + 0x130 + 0x20 + read-write + 0x00000000 + + + CSR14 + CSR14 + 0 + 32 + + + + + CSR15 + CSR15 + context swap registers + 0x134 + 0x20 + read-write + 0x00000000 + + + CSR15 + CSR15 + 0 + 32 + + + + + CSR16 + CSR16 + context swap registers + 0x138 + 0x20 + read-write + 0x00000000 + + + CSR16 + CSR16 + 0 + 32 + + + + + CSR17 + CSR17 + context swap registers + 0x13C + 0x20 + read-write + 0x00000000 + + + CSR17 + CSR17 + 0 + 32 + + + + + CSR18 + CSR18 + context swap registers + 0x140 + 0x20 + read-write + 0x00000000 + + + CSR18 + CSR18 + 0 + 32 + + + + + CSR19 + CSR19 + context swap registers + 0x144 + 0x20 + read-write + 0x00000000 + + + CSR19 + CSR19 + 0 + 32 + + + + + CSR20 + CSR20 + context swap registers + 0x148 + 0x20 + read-write + 0x00000000 + + + CSR20 + CSR20 + 0 + 32 + + + + + CSR21 + CSR21 + context swap registers + 0x14C + 0x20 + read-write + 0x00000000 + + + CSR21 + CSR21 + 0 + 32 + + + + + CSR22 + CSR22 + context swap registers + 0x150 + 0x20 + read-write + 0x00000000 + + + CSR22 + CSR22 + 0 + 32 + + + + + CSR23 + CSR23 + context swap registers + 0x154 + 0x20 + read-write + 0x00000000 + + + CSR23 + CSR23 + 0 + 32 + + + + + CSR24 + CSR24 + context swap registers + 0x158 + 0x20 + read-write + 0x00000000 + + + CSR24 + CSR24 + 0 + 32 + + + + + CSR25 + CSR25 + context swap registers + 0x15C + 0x20 + read-write + 0x00000000 + + + CSR25 + CSR25 + 0 + 32 + + + + + CSR26 + CSR26 + context swap registers + 0x160 + 0x20 + read-write + 0x00000000 + + + CSR26 + CSR26 + 0 + 32 + + + + + CSR27 + CSR27 + context swap registers + 0x164 + 0x20 + read-write + 0x00000000 + + + CSR27 + CSR27 + 0 + 32 + + + + + CSR28 + CSR28 + context swap registers + 0x168 + 0x20 + read-write + 0x00000000 + + + CSR28 + CSR28 + 0 + 32 + + + + + CSR29 + CSR29 + context swap registers + 0x16C + 0x20 + read-write + 0x00000000 + + + CSR29 + CSR29 + 0 + 32 + + + + + CSR30 + CSR30 + context swap registers + 0x170 + 0x20 + read-write + 0x00000000 + + + CSR30 + CSR30 + 0 + 32 + + + + + CSR31 + CSR31 + context swap registers + 0x174 + 0x20 + read-write + 0x00000000 + + + CSR31 + CSR31 + 0 + 32 + + + + + CSR32 + CSR32 + context swap registers + 0x178 + 0x20 + read-write + 0x00000000 + + + CSR32 + CSR32 + 0 + 32 + + + + + CSR33 + CSR33 + context swap registers + 0x17C + 0x20 + read-write + 0x00000000 + + + CSR33 + CSR33 + 0 + 32 + + + + + CSR34 + CSR34 + context swap registers + 0x180 + 0x20 + read-write + 0x00000000 + + + CSR34 + CSR34 + 0 + 32 + + + + + CSR35 + CSR35 + context swap registers + 0x184 + 0x20 + read-write + 0x00000000 + + + CSR35 + CSR35 + 0 + 32 + + + + + CSR36 + CSR36 + context swap registers + 0x188 + 0x20 + read-write + 0x00000000 + + + CSR36 + CSR36 + 0 + 32 + + + + + CSR37 + CSR37 + context swap registers + 0x18C + 0x20 + read-write + 0x00000000 + + + CSR37 + CSR37 + 0 + 32 + + + + + CSR38 + CSR38 + context swap registers + 0x190 + 0x20 + read-write + 0x00000000 + + + CSR38 + CSR38 + 0 + 32 + + + + + CSR39 + CSR39 + context swap registers + 0x194 + 0x20 + read-write + 0x00000000 + + + CSR39 + CSR39 + 0 + 32 + + + + + CSR40 + CSR40 + context swap registers + 0x198 + 0x20 + read-write + 0x00000000 + + + CSR40 + CSR40 + 0 + 32 + + + + + CSR41 + CSR41 + context swap registers + 0x19C + 0x20 + read-write + 0x00000000 + + + CSR41 + CSR41 + 0 + 32 + + + + + CSR42 + CSR42 + context swap registers + 0x1A0 + 0x20 + read-write + 0x00000000 + + + CSR42 + CSR42 + 0 + 32 + + + + + CSR43 + CSR43 + context swap registers + 0x1A4 + 0x20 + read-write + 0x00000000 + + + CSR43 + CSR43 + 0 + 32 + + + + + CSR44 + CSR44 + context swap registers + 0x1A8 + 0x20 + read-write + 0x00000000 + + + CSR44 + CSR44 + 0 + 32 + + + + + CSR45 + CSR45 + context swap registers + 0x1AC + 0x20 + read-write + 0x00000000 + + + CSR45 + CSR45 + 0 + 32 + + + + + CSR46 + CSR46 + context swap registers + 0x1B0 + 0x20 + read-write + 0x00000000 + + + CSR46 + CSR46 + 0 + 32 + + + + + CSR47 + CSR47 + context swap registers + 0x1B4 + 0x20 + read-write + 0x00000000 + + + CSR47 + CSR47 + 0 + 32 + + + + + CSR48 + CSR48 + context swap registers + 0x1B8 + 0x20 + read-write + 0x00000000 + + + CSR48 + CSR48 + 0 + 32 + + + + + CSR49 + CSR49 + context swap registers + 0x1BC + 0x20 + read-write + 0x00000000 + + + CSR49 + CSR49 + 0 + 32 + + + + + CSR50 + CSR50 + context swap registers + 0x1C0 + 0x20 + read-write + 0x00000000 + + + CSR50 + CSR50 + 0 + 32 + + + + + CSR51 + CSR51 + context swap registers + 0x1C4 + 0x20 + read-write + 0x00000000 + + + CSR51 + CSR51 + 0 + 32 + + + + + CSR52 + CSR52 + context swap registers + 0x1C8 + 0x20 + read-write + 0x00000000 + + + CSR52 + CSR52 + 0 + 32 + + + + + CSR53 + CSR53 + context swap registers + 0x1CC + 0x20 + read-write + 0x00000000 + + + CSR53 + CSR53 + 0 + 32 + + + + + HASH_HR0 + HASH_HR0 + HASH digest register + 0x310 + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HASH_HR1 + HASH_HR1 + read-only + 0x314 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HASH_HR2 + HASH_HR2 + read-only + 0x318 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HASH_HR3 + HASH_HR3 + read-only + 0x31C + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HASH_HR4 + HASH_HR4 + read-only + 0x320 + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + HASH_HR5 + HASH_HR5 + read-only + 0x324 + 0x20 + read-only + 0x00000000 + + + H5 + H5 + 0 + 32 + + + + + HASH_HR6 + HASH_HR6 + read-only + 0x328 + 0x20 + read-only + 0x00000000 + + + H6 + H6 + 0 + 32 + + + + + HASH_HR7 + HASH_HR7 + read-only + 0x32C + 0x20 + read-only + 0x00000000 + + + H7 + H7 + 0 + 32 + + + + + + + CRYP + Cryptographic processor + CRYP + 0x50060000 + + 0x0 + 0x400 + registers + + + CRYP + CRYP crypto global interrupt + 79 + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + ALGODIR + Algorithm direction + 2 + 1 + read-write + + + ALGOMODE0 + Algorithm mode + 3 + 3 + read-write + + + DATATYPE + Data type selection + 6 + 2 + read-write + + + KEYSIZE + Key size selection (AES mode + only) + 8 + 2 + read-write + + + FFLUSH + FIFO flush + 14 + 1 + write-only + + + CRYPEN + Cryptographic processor + enable + 15 + 1 + read-write + + + GCM_CCMPH + GCM_CCMPH + 16 + 2 + read-write + + + ALGOMODE3 + ALGOMODE + 19 + 1 + read-write + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x00000003 + + + BUSY + Busy bit + 4 + 1 + + + OFFU + Output FIFO full + 3 + 1 + + + OFNE + Output FIFO not empty + 2 + 1 + + + IFNF + Input FIFO not full + 1 + 1 + + + IFEM + Input FIFO empty + 0 + 1 + + + + + DIN + DIN + data input register + 0x8 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + DOUT + DOUT + data output register + 0xC + 0x20 + read-only + 0x00000000 + + + DATAOUT + Data output + 0 + 32 + + + + + DMACR + DMACR + DMA control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DOEN + DMA output enable + 1 + 1 + + + DIEN + DMA input enable + 0 + 1 + + + + + IMSCR + IMSCR + interrupt mask set/clear + register + 0x14 + 0x20 + read-write + 0x00000000 + + + OUTIM + Output FIFO service interrupt + mask + 1 + 1 + + + INIM + Input FIFO service interrupt + mask + 0 + 1 + + + + + RISR + RISR + raw interrupt status register + 0x18 + 0x20 + read-only + 0x00000001 + + + OUTRIS + Output FIFO service raw interrupt + status + 1 + 1 + + + INRIS + Input FIFO service raw interrupt + status + 0 + 1 + + + + + MISR + MISR + masked interrupt status + register + 0x1C + 0x20 + read-only + 0x00000000 + + + OUTMIS + Output FIFO service masked interrupt + status + 1 + 1 + + + INMIS + Input FIFO service masked interrupt + status + 0 + 1 + + + + + K0LR + K0LR + key registers + 0x20 + 0x20 + write-only + 0x00000000 + + + b224 + b224 + 0 + 1 + + + b225 + b225 + 1 + 1 + + + b226 + b226 + 2 + 1 + + + b227 + b227 + 3 + 1 + + + b228 + b228 + 4 + 1 + + + b229 + b229 + 5 + 1 + + + b230 + b230 + 6 + 1 + + + b231 + b231 + 7 + 1 + + + b232 + b232 + 8 + 1 + + + b233 + b233 + 9 + 1 + + + b234 + b234 + 10 + 1 + + + b235 + b235 + 11 + 1 + + + b236 + b236 + 12 + 1 + + + b237 + b237 + 13 + 1 + + + b238 + b238 + 14 + 1 + + + b239 + b239 + 15 + 1 + + + b240 + b240 + 16 + 1 + + + b241 + b241 + 17 + 1 + + + b242 + b242 + 18 + 1 + + + b243 + b243 + 19 + 1 + + + b244 + b244 + 20 + 1 + + + b245 + b245 + 21 + 1 + + + b246 + b246 + 22 + 1 + + + b247 + b247 + 23 + 1 + + + b248 + b248 + 24 + 1 + + + b249 + b249 + 25 + 1 + + + b250 + b250 + 26 + 1 + + + b251 + b251 + 27 + 1 + + + b252 + b252 + 28 + 1 + + + b253 + b253 + 29 + 1 + + + b254 + b254 + 30 + 1 + + + b255 + b255 + 31 + 1 + + + + + K0RR + K0RR + key registers + 0x24 + 0x20 + write-only + 0x00000000 + + + b192 + b192 + 0 + 1 + + + b193 + b193 + 1 + 1 + + + b194 + b194 + 2 + 1 + + + b195 + b195 + 3 + 1 + + + b196 + b196 + 4 + 1 + + + b197 + b197 + 5 + 1 + + + b198 + b198 + 6 + 1 + + + b199 + b199 + 7 + 1 + + + b200 + b200 + 8 + 1 + + + b201 + b201 + 9 + 1 + + + b202 + b202 + 10 + 1 + + + b203 + b203 + 11 + 1 + + + b204 + b204 + 12 + 1 + + + b205 + b205 + 13 + 1 + + + b206 + b206 + 14 + 1 + + + b207 + b207 + 15 + 1 + + + b208 + b208 + 16 + 1 + + + b209 + b209 + 17 + 1 + + + b210 + b210 + 18 + 1 + + + b211 + b211 + 19 + 1 + + + b212 + b212 + 20 + 1 + + + b213 + b213 + 21 + 1 + + + b214 + b214 + 22 + 1 + + + b215 + b215 + 23 + 1 + + + b216 + b216 + 24 + 1 + + + b217 + b217 + 25 + 1 + + + b218 + b218 + 26 + 1 + + + b219 + b219 + 27 + 1 + + + b220 + b220 + 28 + 1 + + + b221 + b221 + 29 + 1 + + + b222 + b222 + 30 + 1 + + + b223 + b223 + 31 + 1 + + + + + K1LR + K1LR + key registers + 0x28 + 0x20 + write-only + 0x00000000 + + + b160 + b160 + 0 + 1 + + + b161 + b161 + 1 + 1 + + + b162 + b162 + 2 + 1 + + + b163 + b163 + 3 + 1 + + + b164 + b164 + 4 + 1 + + + b165 + b165 + 5 + 1 + + + b166 + b166 + 6 + 1 + + + b167 + b167 + 7 + 1 + + + b168 + b168 + 8 + 1 + + + b169 + b169 + 9 + 1 + + + b170 + b170 + 10 + 1 + + + b171 + b171 + 11 + 1 + + + b172 + b172 + 12 + 1 + + + b173 + b173 + 13 + 1 + + + b174 + b174 + 14 + 1 + + + b175 + b175 + 15 + 1 + + + b176 + b176 + 16 + 1 + + + b177 + b177 + 17 + 1 + + + b178 + b178 + 18 + 1 + + + b179 + b179 + 19 + 1 + + + b180 + b180 + 20 + 1 + + + b181 + b181 + 21 + 1 + + + b182 + b182 + 22 + 1 + + + b183 + b183 + 23 + 1 + + + b184 + b184 + 24 + 1 + + + b185 + b185 + 25 + 1 + + + b186 + b186 + 26 + 1 + + + b187 + b187 + 27 + 1 + + + b188 + b188 + 28 + 1 + + + b189 + b189 + 29 + 1 + + + b190 + b190 + 30 + 1 + + + b191 + b191 + 31 + 1 + + + + + K1RR + K1RR + key registers + 0x2C + 0x20 + write-only + 0x00000000 + + + b128 + b128 + 0 + 1 + + + b129 + b129 + 1 + 1 + + + b130 + b130 + 2 + 1 + + + b131 + b131 + 3 + 1 + + + b132 + b132 + 4 + 1 + + + b133 + b133 + 5 + 1 + + + b134 + b134 + 6 + 1 + + + b135 + b135 + 7 + 1 + + + b136 + b136 + 8 + 1 + + + b137 + b137 + 9 + 1 + + + b138 + b138 + 10 + 1 + + + b139 + b139 + 11 + 1 + + + b140 + b140 + 12 + 1 + + + b141 + b141 + 13 + 1 + + + b142 + b142 + 14 + 1 + + + b143 + b143 + 15 + 1 + + + b144 + b144 + 16 + 1 + + + b145 + b145 + 17 + 1 + + + b146 + b146 + 18 + 1 + + + b147 + b147 + 19 + 1 + + + b148 + b148 + 20 + 1 + + + b149 + b149 + 21 + 1 + + + b150 + b150 + 22 + 1 + + + b151 + b151 + 23 + 1 + + + b152 + b152 + 24 + 1 + + + b153 + b153 + 25 + 1 + + + b154 + b154 + 26 + 1 + + + b155 + b155 + 27 + 1 + + + b156 + b156 + 28 + 1 + + + b157 + b157 + 29 + 1 + + + b158 + b158 + 30 + 1 + + + b159 + b159 + 31 + 1 + + + + + K2LR + K2LR + key registers + 0x30 + 0x20 + write-only + 0x00000000 + + + b96 + b96 + 0 + 1 + + + b97 + b97 + 1 + 1 + + + b98 + b98 + 2 + 1 + + + b99 + b99 + 3 + 1 + + + b100 + b100 + 4 + 1 + + + b101 + b101 + 5 + 1 + + + b102 + b102 + 6 + 1 + + + b103 + b103 + 7 + 1 + + + b104 + b104 + 8 + 1 + + + b105 + b105 + 9 + 1 + + + b106 + b106 + 10 + 1 + + + b107 + b107 + 11 + 1 + + + b108 + b108 + 12 + 1 + + + b109 + b109 + 13 + 1 + + + b110 + b110 + 14 + 1 + + + b111 + b111 + 15 + 1 + + + b112 + b112 + 16 + 1 + + + b113 + b113 + 17 + 1 + + + b114 + b114 + 18 + 1 + + + b115 + b115 + 19 + 1 + + + b116 + b116 + 20 + 1 + + + b117 + b117 + 21 + 1 + + + b118 + b118 + 22 + 1 + + + b119 + b119 + 23 + 1 + + + b120 + b120 + 24 + 1 + + + b121 + b121 + 25 + 1 + + + b122 + b122 + 26 + 1 + + + b123 + b123 + 27 + 1 + + + b124 + b124 + 28 + 1 + + + b125 + b125 + 29 + 1 + + + b126 + b126 + 30 + 1 + + + b127 + b127 + 31 + 1 + + + + + K2RR + K2RR + key registers + 0x34 + 0x20 + write-only + 0x00000000 + + + b64 + b64 + 0 + 1 + + + b65 + b65 + 1 + 1 + + + b66 + b66 + 2 + 1 + + + b67 + b67 + 3 + 1 + + + b68 + b68 + 4 + 1 + + + b69 + b69 + 5 + 1 + + + b70 + b70 + 6 + 1 + + + b71 + b71 + 7 + 1 + + + b72 + b72 + 8 + 1 + + + b73 + b73 + 9 + 1 + + + b74 + b74 + 10 + 1 + + + b75 + b75 + 11 + 1 + + + b76 + b76 + 12 + 1 + + + b77 + b77 + 13 + 1 + + + b78 + b78 + 14 + 1 + + + b79 + b79 + 15 + 1 + + + b80 + b80 + 16 + 1 + + + b81 + b81 + 17 + 1 + + + b82 + b82 + 18 + 1 + + + b83 + b83 + 19 + 1 + + + b84 + b84 + 20 + 1 + + + b85 + b85 + 21 + 1 + + + b86 + b86 + 22 + 1 + + + b87 + b87 + 23 + 1 + + + b88 + b88 + 24 + 1 + + + b89 + b89 + 25 + 1 + + + b90 + b90 + 26 + 1 + + + b91 + b91 + 27 + 1 + + + b92 + b92 + 28 + 1 + + + b93 + b93 + 29 + 1 + + + b94 + b94 + 30 + 1 + + + b95 + b95 + 31 + 1 + + + + + K3LR + K3LR + key registers + 0x38 + 0x20 + write-only + 0x00000000 + + + b32 + b32 + 0 + 1 + + + b33 + b33 + 1 + 1 + + + b34 + b34 + 2 + 1 + + + b35 + b35 + 3 + 1 + + + b36 + b36 + 4 + 1 + + + b37 + b37 + 5 + 1 + + + b38 + b38 + 6 + 1 + + + b39 + b39 + 7 + 1 + + + b40 + b40 + 8 + 1 + + + b41 + b41 + 9 + 1 + + + b42 + b42 + 10 + 1 + + + b43 + b43 + 11 + 1 + + + b44 + b44 + 12 + 1 + + + b45 + b45 + 13 + 1 + + + b46 + b46 + 14 + 1 + + + b47 + b47 + 15 + 1 + + + b48 + b48 + 16 + 1 + + + b49 + b49 + 17 + 1 + + + b50 + b50 + 18 + 1 + + + b51 + b51 + 19 + 1 + + + b52 + b52 + 20 + 1 + + + b53 + b53 + 21 + 1 + + + b54 + b54 + 22 + 1 + + + b55 + b55 + 23 + 1 + + + b56 + b56 + 24 + 1 + + + b57 + b57 + 25 + 1 + + + b58 + b58 + 26 + 1 + + + b59 + b59 + 27 + 1 + + + b60 + b60 + 28 + 1 + + + b61 + b61 + 29 + 1 + + + b62 + b62 + 30 + 1 + + + b63 + b63 + 31 + 1 + + + + + K3RR + K3RR + key registers + 0x3C + 0x20 + write-only + 0x00000000 + + + b0 + b0 + 0 + 1 + + + b1 + b1 + 1 + 1 + + + b2 + b2 + 2 + 1 + + + b3 + b3 + 3 + 1 + + + b4 + b4 + 4 + 1 + + + b5 + b5 + 5 + 1 + + + b6 + b6 + 6 + 1 + + + b7 + b7 + 7 + 1 + + + b8 + b8 + 8 + 1 + + + b9 + b9 + 9 + 1 + + + b10 + b10 + 10 + 1 + + + b11 + b11 + 11 + 1 + + + b12 + b12 + 12 + 1 + + + b13 + b13 + 13 + 1 + + + b14 + b14 + 14 + 1 + + + b15 + b15 + 15 + 1 + + + b16 + b16 + 16 + 1 + + + b17 + b17 + 17 + 1 + + + b18 + b18 + 18 + 1 + + + b19 + b19 + 19 + 1 + + + b20 + b20 + 20 + 1 + + + b21 + b21 + 21 + 1 + + + b22 + b22 + 22 + 1 + + + b23 + b23 + 23 + 1 + + + b24 + b24 + 24 + 1 + + + b25 + b25 + 25 + 1 + + + b26 + b26 + 26 + 1 + + + b27 + b27 + 27 + 1 + + + b28 + b28 + 28 + 1 + + + b29 + b29 + 29 + 1 + + + b30 + b30 + 30 + 1 + + + b31 + b31 + 31 + 1 + + + + + IV0LR + IV0LR + initialization vector + registers + 0x40 + 0x20 + read-write + 0x00000000 + + + IV31 + IV31 + 0 + 1 + + + IV30 + IV30 + 1 + 1 + + + IV29 + IV29 + 2 + 1 + + + IV28 + IV28 + 3 + 1 + + + IV27 + IV27 + 4 + 1 + + + IV26 + IV26 + 5 + 1 + + + IV25 + IV25 + 6 + 1 + + + IV24 + IV24 + 7 + 1 + + + IV23 + IV23 + 8 + 1 + + + IV22 + IV22 + 9 + 1 + + + IV21 + IV21 + 10 + 1 + + + IV20 + IV20 + 11 + 1 + + + IV19 + IV19 + 12 + 1 + + + IV18 + IV18 + 13 + 1 + + + IV17 + IV17 + 14 + 1 + + + IV16 + IV16 + 15 + 1 + + + IV15 + IV15 + 16 + 1 + + + IV14 + IV14 + 17 + 1 + + + IV13 + IV13 + 18 + 1 + + + IV12 + IV12 + 19 + 1 + + + IV11 + IV11 + 20 + 1 + + + IV10 + IV10 + 21 + 1 + + + IV9 + IV9 + 22 + 1 + + + IV8 + IV8 + 23 + 1 + + + IV7 + IV7 + 24 + 1 + + + IV6 + IV6 + 25 + 1 + + + IV5 + IV5 + 26 + 1 + + + IV4 + IV4 + 27 + 1 + + + IV3 + IV3 + 28 + 1 + + + IV2 + IV2 + 29 + 1 + + + IV1 + IV1 + 30 + 1 + + + IV0 + IV0 + 31 + 1 + + + + + IV0RR + IV0RR + initialization vector + registers + 0x44 + 0x20 + read-write + 0x00000000 + + + IV63 + IV63 + 0 + 1 + + + IV62 + IV62 + 1 + 1 + + + IV61 + IV61 + 2 + 1 + + + IV60 + IV60 + 3 + 1 + + + IV59 + IV59 + 4 + 1 + + + IV58 + IV58 + 5 + 1 + + + IV57 + IV57 + 6 + 1 + + + IV56 + IV56 + 7 + 1 + + + IV55 + IV55 + 8 + 1 + + + IV54 + IV54 + 9 + 1 + + + IV53 + IV53 + 10 + 1 + + + IV52 + IV52 + 11 + 1 + + + IV51 + IV51 + 12 + 1 + + + IV50 + IV50 + 13 + 1 + + + IV49 + IV49 + 14 + 1 + + + IV48 + IV48 + 15 + 1 + + + IV47 + IV47 + 16 + 1 + + + IV46 + IV46 + 17 + 1 + + + IV45 + IV45 + 18 + 1 + + + IV44 + IV44 + 19 + 1 + + + IV43 + IV43 + 20 + 1 + + + IV42 + IV42 + 21 + 1 + + + IV41 + IV41 + 22 + 1 + + + IV40 + IV40 + 23 + 1 + + + IV39 + IV39 + 24 + 1 + + + IV38 + IV38 + 25 + 1 + + + IV37 + IV37 + 26 + 1 + + + IV36 + IV36 + 27 + 1 + + + IV35 + IV35 + 28 + 1 + + + IV34 + IV34 + 29 + 1 + + + IV33 + IV33 + 30 + 1 + + + IV32 + IV32 + 31 + 1 + + + + + IV1LR + IV1LR + initialization vector + registers + 0x48 + 0x20 + read-write + 0x00000000 + + + IV95 + IV95 + 0 + 1 + + + IV94 + IV94 + 1 + 1 + + + IV93 + IV93 + 2 + 1 + + + IV92 + IV92 + 3 + 1 + + + IV91 + IV91 + 4 + 1 + + + IV90 + IV90 + 5 + 1 + + + IV89 + IV89 + 6 + 1 + + + IV88 + IV88 + 7 + 1 + + + IV87 + IV87 + 8 + 1 + + + IV86 + IV86 + 9 + 1 + + + IV85 + IV85 + 10 + 1 + + + IV84 + IV84 + 11 + 1 + + + IV83 + IV83 + 12 + 1 + + + IV82 + IV82 + 13 + 1 + + + IV81 + IV81 + 14 + 1 + + + IV80 + IV80 + 15 + 1 + + + IV79 + IV79 + 16 + 1 + + + IV78 + IV78 + 17 + 1 + + + IV77 + IV77 + 18 + 1 + + + IV76 + IV76 + 19 + 1 + + + IV75 + IV75 + 20 + 1 + + + IV74 + IV74 + 21 + 1 + + + IV73 + IV73 + 22 + 1 + + + IV72 + IV72 + 23 + 1 + + + IV71 + IV71 + 24 + 1 + + + IV70 + IV70 + 25 + 1 + + + IV69 + IV69 + 26 + 1 + + + IV68 + IV68 + 27 + 1 + + + IV67 + IV67 + 28 + 1 + + + IV66 + IV66 + 29 + 1 + + + IV65 + IV65 + 30 + 1 + + + IV64 + IV64 + 31 + 1 + + + + + IV1RR + IV1RR + initialization vector + registers + 0x4C + 0x20 + read-write + 0x00000000 + + + IV127 + IV127 + 0 + 1 + + + IV126 + IV126 + 1 + 1 + + + IV125 + IV125 + 2 + 1 + + + IV124 + IV124 + 3 + 1 + + + IV123 + IV123 + 4 + 1 + + + IV122 + IV122 + 5 + 1 + + + IV121 + IV121 + 6 + 1 + + + IV120 + IV120 + 7 + 1 + + + IV119 + IV119 + 8 + 1 + + + IV118 + IV118 + 9 + 1 + + + IV117 + IV117 + 10 + 1 + + + IV116 + IV116 + 11 + 1 + + + IV115 + IV115 + 12 + 1 + + + IV114 + IV114 + 13 + 1 + + + IV113 + IV113 + 14 + 1 + + + IV112 + IV112 + 15 + 1 + + + IV111 + IV111 + 16 + 1 + + + IV110 + IV110 + 17 + 1 + + + IV109 + IV109 + 18 + 1 + + + IV108 + IV108 + 19 + 1 + + + IV107 + IV107 + 20 + 1 + + + IV106 + IV106 + 21 + 1 + + + IV105 + IV105 + 22 + 1 + + + IV104 + IV104 + 23 + 1 + + + IV103 + IV103 + 24 + 1 + + + IV102 + IV102 + 25 + 1 + + + IV101 + IV101 + 26 + 1 + + + IV100 + IV100 + 27 + 1 + + + IV99 + IV99 + 28 + 1 + + + IV98 + IV98 + 29 + 1 + + + IV97 + IV97 + 30 + 1 + + + IV96 + IV96 + 31 + 1 + + + + + CSGCMCCM0R + CSGCMCCM0R + context swap register + 0x50 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM0R + CSGCMCCM0R + 0 + 32 + + + + + CSGCMCCM1R + CSGCMCCM1R + context swap register + 0x54 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM1R + CSGCMCCM1R + 0 + 32 + + + + + CSGCMCCM2R + CSGCMCCM2R + context swap register + 0x58 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM2R + CSGCMCCM2R + 0 + 32 + + + + + CSGCMCCM3R + CSGCMCCM3R + context swap register + 0x5C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM3R + CSGCMCCM3R + 0 + 32 + + + + + CSGCMCCM4R + CSGCMCCM4R + context swap register + 0x60 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM4R + CSGCMCCM4R + 0 + 32 + + + + + CSGCMCCM5R + CSGCMCCM5R + context swap register + 0x64 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM5R + CSGCMCCM5R + 0 + 32 + + + + + CSGCMCCM6R + CSGCMCCM6R + context swap register + 0x68 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM6R + CSGCMCCM6R + 0 + 32 + + + + + CSGCMCCM7R + CSGCMCCM7R + context swap register + 0x6C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM7R + CSGCMCCM7R + 0 + 32 + + + + + CSGCM0R + CSGCM0R + context swap register + 0x70 + 0x20 + read-write + 0x00000000 + + + CSGCM0R + CSGCM0R + 0 + 32 + + + + + CSGCM1R + CSGCM1R + context swap register + 0x74 + 0x20 + read-write + 0x00000000 + + + CSGCM1R + CSGCM1R + 0 + 32 + + + + + CSGCM2R + CSGCM2R + context swap register + 0x78 + 0x20 + read-write + 0x00000000 + + + CSGCM2R + CSGCM2R + 0 + 32 + + + + + CSGCM3R + CSGCM3R + context swap register + 0x7C + 0x20 + read-write + 0x00000000 + + + CSGCM3R + CSGCM3R + 0 + 32 + + + + + CSGCM4R + CSGCM4R + context swap register + 0x80 + 0x20 + read-write + 0x00000000 + + + CSGCM4R + CSGCM4R + 0 + 32 + + + + + CSGCM5R + CSGCM5R + context swap register + 0x84 + 0x20 + read-write + 0x00000000 + + + CSGCM5R + CSGCM5R + 0 + 32 + + + + + CSGCM6R + CSGCM6R + context swap register + 0x88 + 0x20 + read-write + 0x00000000 + + + CSGCM6R + CSGCM6R + 0 + 32 + + + + + CSGCM7R + CSGCM7R + context swap register + 0x8C + 0x20 + read-write + 0x00000000 + + + CSGCM7R + CSGCM7R + 0 + 32 + + + + + + + DCMI + Digital camera interface + DCMI + 0x50050000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ENABLE + DCMI enable + 14 + 1 + + + EDM + Extended data mode + 10 + 2 + + + FCRC + Frame capture rate control + 8 + 2 + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + + + PCKPOL + Pixel clock polarity + 5 + 1 + + + ESS + Embedded synchronization + select + 4 + 1 + + + JPEG + JPEG format + 3 + 1 + + + CROP + Crop feature + 2 + 1 + + + CM + Capture mode + 1 + 1 + + + CAPTURE + Capture enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + ETHMACRST + Ethernet MAC reset + 25 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOIRST + IO port I reset + 8 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + RNGRST + Random number generator module + reset + 6 + 1 + + + HSAHRST + Hash module reset + 5 + 1 + + + CRYPRST + Cryptographic module reset + 4 + 1 + + + DCMIRST + Camera interface reset + 0 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FMCRST + Flexible static memory controller module + reset + 0 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM2 reset + 0 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 reset + 0 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + SDIORST + SDIO reset + 11 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM11RST + TIM11 reset + 18 + 1 + + + SPI5RST + SPI5 reset + 20 + 1 + + + SPI6RST + SPI6 reset + 21 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + ETHMACPTPEN + Ethernet PTP clock enable + 28 + 1 + + + ETHMACRXEN + Ethernet Reception clock + enable + 27 + 1 + + + ETHMACTXEN + Ethernet Transmission clock + enable + 26 + 1 + + + ETHMACEN + Ethernet MAC clock enable + 25 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOIEN + IO port I clock enable + 8 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + RNGEN + Random number generator clock + enable + 6 + 1 + + + HASHEN + Hash modules clock enable + 5 + 1 + + + CRYPEN + Cryptographic modules clock + enable + 4 + 1 + + + DCMIEN + Camera interface enable + 0 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FMCEN + Flexible static memory controller module + clock enable + 0 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + CAN2EN + CAN 2 clock enable + 26 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + UART7ENR + UART7 clock enable + 30 + 1 + + + UART8ENR + UART8 clock enable + 31 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SDIOEN + SDIO clock enable + 11 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4ENR + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + SPI5ENR + SPI5 clock enable + 20 + 1 + + + SPI6ENR + SPI6 clock enable + 21 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOILPEN + IO port I clock enable during Sleep + mode + 8 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + SRAM3LPEN + SRAM 3 interface clock enable during + Sleep mode + 19 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + ETHMACLPEN + Ethernet MAC clock enable during Sleep + mode + 25 + 1 + + + ETHMACTXLPEN + Ethernet transmission clock enable + during Sleep mode + 26 + 1 + + + ETHMACRXLPEN + Ethernet reception clock enable during + Sleep mode + 27 + 1 + + + ETHMACPTPLPEN + Ethernet PTP clock enable during Sleep + mode + 28 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + RNGLPEN + Random number generator clock enable + during Sleep mode + 6 + 1 + + + HASHLPEN + Hash modules clock enable during Sleep + mode + 5 + 1 + + + CRYPLPEN + Cryptography modules clock enable during + Sleep mode + 4 + 1 + + + DCMILPEN + Camera interface enable during Sleep + mode + 0 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FMCLPEN + Flexible static memory controller module + clock enable during Sleep mode + 0 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during Sleep + mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during Sleep + mode + 31 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + SDIOLPEN + SDIO clock enable during Sleep + mode + 11 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI 4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + SPI5LPEN + SPI 5 clock enable during Sleep + mode + 20 + 1 + + + SPI6LPEN + SPI 6 clock enable during Sleep + mode + 21 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SRx + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SNx + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + + + GPIOI + General-purpose I/Os + GPIO + 0x40022000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOH + 0x40021C00 + + + GPIOG + 0x40021800 + + + GPIOF + 0x40021400 + + + GPIOE + 0x40021000 + + + GPIOD + 0X40020C00 + + + GPIOC + 0x40020800 + + + GPIOJ + 0x40022400 + + + GPIOK + 0x40022800 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + MEM_MODE + 0 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + Ethernet PHY interface + selection + 23 + 1 + + + ADC1DC2 + ADC1DC2 + 16 + 1 + + + ADC2DC2 + ADC2DC2 + 17 + 1 + + + ADC3DC2 + ADC3DC2 + 18 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + DFF + Data frame format + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + FRF + Frame format + 4 + 1 + + + SSOE + SS output enable + 2 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + TIFRFE + TI frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + I2S2ext + 0x40003400 + + + I2S3ext + 0x40004000 + + + SPI4 + 0x40013400 + + SPI4 + SPI 4 global interrupt + 84 + + + + SPI5 + 0x40015000 + + SPI5 + SPI 5 global interrupt + 85 + + + + SPI6 + 0x40015400 + + SPI6 + SPI 6 global interrupt + 86 + + + + SDIO + Secure digital input/output + interface + SDIO + 0x40012C00 + + 0x0 + 0x400 + registers + + + SDIO + SDIO global interrupt + 49 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + CE_ATACMD + CE-ATA command + 14 + 1 + + + nIEN + not Interrupt Enable + 13 + 1 + + + ENCMDcompl + Enable CMD completion + 12 + 1 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal). + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 132. + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table 132. + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table 132. + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table 132. + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer. + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + CEATAEND + CE-ATA command completion signal + received for CMD61 + 23 + 1 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + STBITERR + Start bit not detected on all data + signals in wide bus mode + 9 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEATAENDC + CEATAEND flag clear bit + 23 + 1 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + STBITERRC + STBITERR flag clear bit + 9 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + CEATAENDIE + CE-ATA command completion signal + received interrupt enable + 23 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + STBITERRIE + Start bit error interrupt + enable + 9 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO. + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x51 + registers + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC2 + 0x40012100 + + + ADC3 + 0x40012200 + + ADC + ADC3 global interrupts + 18 + + + + USART6 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011400 + + 0x0 + 0x400 + registers + + + USART6 + USART6 global interrupt + 71 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + CTS + CTS flag + 9 + 1 + read-write + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x18 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + + + USART1 + 0x40011000 + + USART1 + USART1 global interrupt + 37 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + UART7 + 0x40007800 + + UART7 + UART 7 global interrupt + 82 + + + + UART8 + 0x40007C00 + + UART8 + UART 8 global interrupt + 83 + + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTC_Alarm + RTC Alarms (A and B) through EXTI line + interrupt + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + COE + Calibration output enable + 23 + 1 + + + OSEL + Output selection + 21 + 2 + + + POL + Output polarity + 20 + 1 + + + BKP + Backup + 18 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + DCE + Coarse digital calibration + enable + 7 + 1 + + + FMT + Hour format + 6 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + TAMPER2 detection flag + 14 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + CALIBR + CALIBR + calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + DCS + Digital calibration sign + 7 + 1 + + + DC + Digital calibration + 0 + 5 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAFCR + TAFCR + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + UART4 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40004C00 + + 0x0 + 0x400 + registers + + + UART4 + UART4 global interrupt + 52 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0xD + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + + + TIM8 + 0x40010400 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + ITR1_RMP + Timer Input 4 remap + 10 + 2 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM4 + 0x40000800 + + TIM4 + TIM4 global interrupt + 30 + + + + TIM5 + General-purpose-timers + TIM + 0x40000C00 + + 0x0 + 0x400 + registers + + + TIM5 + TIM5 global interrupt + 50 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + IT4_RMP + Timer Input 4 remap + 6 + 2 + + + + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + + + TIM13 + 0x40001C00 + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + + TIM14 + 0x40002000 + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + + TIM11 + General-purpose-timers + TIM + 0x40014800 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 + (inputmode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + RMP + Input 1 remapping + capability + 0 + 2 + + + + + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + Ethernet_MAC + Ethernet: media access control + (MAC) + Ethernet + 0x40028000 + + 0x0 + 0x61 + registers + + + ETH + Ethernet global interrupt + 61 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + + MACCR + MACCR + Ethernet MAC configuration + register + 0x0 + 0x20 + read-write + 0x0008000 + + + RE + RE + 2 + 1 + + + TE + TE + 3 + 1 + + + DC + DC + 4 + 1 + + + BL + BL + 5 + 2 + + + APCS + APCS + 7 + 1 + + + RD + RD + 9 + 1 + + + IPCO + IPCO + 10 + 1 + + + DM + DM + 11 + 1 + + + LM + LM + 12 + 1 + + + ROD + ROD + 13 + 1 + + + FES + FES + 14 + 1 + + + CSD + CSD + 16 + 1 + + + IFG + IFG + 17 + 3 + + + JD + JD + 22 + 1 + + + WD + WD + 23 + 1 + + + CSTF + CSTF + 25 + 1 + + + + + MACFFR + MACFFR + Ethernet MAC frame filter + register + 0x4 + 0x20 + read-write + 0x00000000 + + + PM + PM + 0 + 1 + + + HU + HU + 1 + 1 + + + HM + HM + 2 + 1 + + + DAIF + DAIF + 3 + 1 + + + RAM + RAM + 4 + 1 + + + BFD + BFD + 5 + 1 + + + PCF + PCF + 6 + 1 + + + SAIF + SAIF + 7 + 1 + + + SAF + SAF + 8 + 1 + + + HPF + HPF + 9 + 1 + + + RA + RA + 31 + 1 + + + + + MACHTHR + MACHTHR + Ethernet MAC hash table high + register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + HTH + 0 + 32 + + + + + MACHTLR + MACHTLR + Ethernet MAC hash table low + register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + HTL + 0 + 32 + + + + + MACMIIAR + MACMIIAR + Ethernet MAC MII address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MB + 0 + 1 + + + MW + MW + 1 + 1 + + + CR + CR + 2 + 3 + + + MR + MR + 6 + 5 + + + PA + PA + 11 + 5 + + + + + MACMIIDR + MACMIIDR + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + TD + TD + 0 + 16 + + + + + MACFCR + MACFCR + Ethernet MAC flow control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB + FCB + 0 + 1 + + + TFCE + TFCE + 1 + 1 + + + RFCE + RFCE + 2 + 1 + + + UPFD + UPFD + 3 + 1 + + + PLT + PLT + 4 + 2 + + + ZQPD + ZQPD + 7 + 1 + + + PT + PT + 16 + 16 + + + + + MACVLANTR + MACVLANTR + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VLANTI + VLANTI + 0 + 16 + + + VLANTC + VLANTC + 16 + 1 + + + + + MACPMTCSR + MACPMTCSR + Ethernet MAC PMT control and status + register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + PD + 0 + 1 + + + MPE + MPE + 1 + 1 + + + WFE + WFE + 2 + 1 + + + MPR + MPR + 5 + 1 + + + WFR + WFR + 6 + 1 + + + GU + GU + 9 + 1 + + + WFFRPR + WFFRPR + 31 + 1 + + + + + MACDBGR + MACDBGR + Ethernet MAC debug register + 0x34 + 0x20 + read-only + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MACSR + MACSR + Ethernet MAC interrupt status + register + 0x38 + 0x20 + 0x00000000 + + + PMTS + PMTS + 3 + 1 + read-only + + + MMCS + MMCS + 4 + 1 + read-only + + + MMCRS + MMCRS + 5 + 1 + read-only + + + MMCTS + MMCTS + 6 + 1 + read-only + + + TSTS + TSTS + 9 + 1 + read-write + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask + register + 0x3C + 0x20 + read-write + 0x00000000 + + + PMTIM + PMTIM + 3 + 1 + + + TSTIM + TSTIM + 9 + 1 + + + + + MACA0HR + MACA0HR + Ethernet MAC address 0 high + register + 0x40 + 0x20 + 0x0010FFFF + + + MACA0H + MAC address0 high + 0 + 16 + read-write + + + MO + Always 1 + 31 + 1 + read-only + + + + + MACA0LR + MACA0LR + Ethernet MAC address 0 low + register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MACA0L + 0 + 0 + 32 + + + + + MACA1HR + MACA1HR + Ethernet MAC address 1 high + register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MACA1H + MACA1H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA1LR + MACA1LR + Ethernet MAC address1 low + register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MACA1LR + MACA1LR + 0 + 32 + + + + + MACA2HR + MACA2HR + Ethernet MAC address 2 high + register + 0x50 + 0x20 + read-write + 0x0000FFFF + + + MAC2AH + MAC2AH + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA2LR + MACA2LR + Ethernet MAC address 2 low + register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MACA2L + MACA2L + 0 + 31 + + + + + MACA3HR + MACA3HR + Ethernet MAC address 3 high + register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MACA3H + MACA3H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3LR + MACA3LR + Ethernet MAC address 3 low + register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MBCA3L + MBCA3L + 0 + 32 + + + + + + + Ethernet_MMC + Ethernet: MAC management counters + Ethernet + 0x40028100 + + 0x0 + 0x400 + registers + + + + MMCCR + MMCCR + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MMCRIR + MMCRIR + Ethernet MMC receive interrupt + register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCES + RFCES + 5 + 1 + + + RFAES + RFAES + 6 + 1 + + + RGUFS + RGUFS + 17 + 1 + + + + + MMCTIR + MMCTIR + Ethernet MMC transmit interrupt + register + 0x8 + 0x20 + read-only + 0x00000000 + + + TGFSCS + TGFSCS + 14 + 1 + + + TGFMSCS + TGFMSCS + 15 + 1 + + + TGFS + TGFS + 21 + 1 + + + + + MMCRIMR + MMCRIMR + Ethernet MMC receive interrupt mask + register + 0xC + 0x20 + read-write + 0x00000000 + + + RFCEM + RFCEM + 5 + 1 + + + RFAEM + RFAEM + 6 + 1 + + + RGUFM + RGUFM + 17 + 1 + + + + + MMCTIMR + MMCTIMR + Ethernet MMC transmit interrupt mask + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TGFSCM + TGFSCM + 14 + 1 + + + TGFMSCM + TGFMSCM + 15 + 1 + + + TGFM + TGFM + 16 + 1 + + + + + MMCTGFSCCR + MMCTGFSCCR + Ethernet MMC transmitted good frames after a + single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + TGFSCC + 0 + 32 + + + + + MMCTGFMSCCR + MMCTGFMSCCR + Ethernet MMC transmitted good frames after + more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + TGFMSCC + 0 + 32 + + + + + MMCTGFCR + MMCTGFCR + Ethernet MMC transmitted good frames counter + register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + HTL + 0 + 32 + + + + + MMCRFCECR + MMCRFCECR + Ethernet MMC received frames with CRC error + counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCFC + RFCFC + 0 + 32 + + + + + MMCRFAECR + MMCRFAECR + Ethernet MMC received frames with alignment + error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + RFAEC + 0 + 32 + + + + + MMCRGUFCR + MMCRGUFCR + MMC received good unicast frames counter + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + RGUFC + 0 + 32 + + + + + + + Ethernet_PTP + Ethernet: Precision time protocol + Ethernet + 0x40028700 + + 0x0 + 0x400 + registers + + + + PTPTSCR + PTPTSCR + Ethernet PTP time stamp control + register + 0x0 + 0x20 + read-write + 0x00002000 + + + TSE + TSE + 0 + 1 + + + TSFCU + TSFCU + 1 + 1 + + + TSPTPPSV2E + TSPTPPSV2E + 10 + 1 + + + TSSPTPOEFE + TSSPTPOEFE + 11 + 1 + + + TSSIPV6FE + TSSIPV6FE + 12 + 1 + + + TSSIPV4FE + TSSIPV4FE + 13 + 1 + + + TSSEME + TSSEME + 14 + 1 + + + TSSMRME + TSSMRME + 15 + 1 + + + TSCNT + TSCNT + 16 + 2 + + + TSPFFMAE + TSPFFMAE + 18 + 1 + + + TSSTI + TSSTI + 2 + 1 + + + TSSTU + TSSTU + 3 + 1 + + + TSITE + TSITE + 4 + 1 + + + TTSARU + TTSARU + 5 + 1 + + + TSSARFE + TSSARFE + 8 + 1 + + + TSSSR + TSSSR + 9 + 1 + + + + + PTPSSIR + PTPSSIR + Ethernet PTP subsecond increment + register + 0x4 + 0x20 + read-write + 0x00000000 + + + STSSI + STSSI + 0 + 8 + + + + + PTPTSHR + PTPTSHR + Ethernet PTP time stamp high + register + 0x8 + 0x20 + read-only + 0x00000000 + + + STS + STS + 0 + 32 + + + + + PTPTSLR + PTPTSLR + Ethernet PTP time stamp low + register + 0xC + 0x20 + read-only + 0x00000000 + + + STSS + STSS + 0 + 31 + + + STPNS + STPNS + 31 + 1 + + + + + PTPTSHUR + PTPTSHUR + Ethernet PTP time stamp high update + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSUS + TSUS + 0 + 32 + + + + + PTPTSLUR + PTPTSLUR + Ethernet PTP time stamp low update + register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSUSS + TSUSS + 0 + 31 + + + TSUPNS + TSUPNS + 31 + 1 + + + + + PTPTSAR + PTPTSAR + Ethernet PTP time stamp addend + register + 0x18 + 0x20 + read-write + 0x00000000 + + + TSA + TSA + 0 + 32 + + + + + PTPTTHR + PTPTTHR + Ethernet PTP target time high + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSH + 0 + 0 + 32 + + + + + PTPTTLR + PTPTTLR + Ethernet PTP target time low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTSL + TTSL + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status + register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control + register + 0x2C + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + + + Ethernet_DMA + Ethernet: DMA controller operation + Ethernet + 0x40029000 + + 0x0 + 0x400 + registers + + + + DMABMR + DMABMR + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x00002101 + + + SR + SR + 0 + 1 + + + DA + DA + 1 + 1 + + + DSL + DSL + 2 + 5 + + + EDFE + EDFE + 7 + 1 + + + PBL + PBL + 8 + 6 + + + RTPR + RTPR + 14 + 2 + + + FB + FB + 16 + 1 + + + RDP + RDP + 17 + 6 + + + USP + USP + 23 + 1 + + + FPM + FPM + 24 + 1 + + + AAB + AAB + 25 + 1 + + + MB + MB + 26 + 1 + + + + + DMATPDR + DMATPDR + Ethernet DMA transmit poll demand + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + TPD + 0 + 32 + + + + + DMARPDR + DMARPDR + EHERNET DMA receive poll demand + register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + RPD + 0 + 32 + + + + + DMARDLAR + DMARDLAR + Ethernet DMA receive descriptor list address + register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + SRL + 0 + 32 + + + + + DMATDLAR + DMATDLAR + Ethernet DMA transmit descriptor list + address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + STL + 0 + 32 + + + + + DMASR + DMASR + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TS + TS + 0 + 1 + read-write + + + TPSS + TPSS + 1 + 1 + read-write + + + TBUS + TBUS + 2 + 1 + read-write + + + TJTS + TJTS + 3 + 1 + read-write + + + ROS + ROS + 4 + 1 + read-write + + + TUS + TUS + 5 + 1 + read-write + + + RS + RS + 6 + 1 + read-write + + + RBUS + RBUS + 7 + 1 + read-write + + + RPSS + RPSS + 8 + 1 + read-write + + + PWTS + PWTS + 9 + 1 + read-write + + + ETS + ETS + 10 + 1 + read-write + + + FBES + FBES + 13 + 1 + read-write + + + ERS + ERS + 14 + 1 + read-write + + + AIS + AIS + 15 + 1 + read-write + + + NIS + NIS + 16 + 1 + read-write + + + RPS + RPS + 17 + 3 + read-only + + + TPS + TPS + 20 + 3 + read-only + + + EBS + EBS + 23 + 3 + read-only + + + MMCS + MMCS + 27 + 1 + read-only + + + PMTS + PMTS + 28 + 1 + read-only + + + TSTS + TSTS + 29 + 1 + read-only + + + + + DMAOMR + DMAOMR + Ethernet DMA operation mode + register + 0x18 + 0x20 + read-write + 0x00000000 + + + SR + SR + 1 + 1 + + + OSF + OSF + 2 + 1 + + + RTC + RTC + 3 + 2 + + + FUGF + FUGF + 6 + 1 + + + FEF + FEF + 7 + 1 + + + ST + ST + 13 + 1 + + + TTC + TTC + 14 + 3 + + + FTF + FTF + 20 + 1 + + + TSF + TSF + 21 + 1 + + + DFRF + DFRF + 24 + 1 + + + RSF + RSF + 25 + 1 + + + DTCEFD + DTCEFD + 26 + 1 + + + + + DMAIER + DMAIER + Ethernet DMA interrupt enable + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + TIE + 0 + 1 + + + TPSIE + TPSIE + 1 + 1 + + + TBUIE + TBUIE + 2 + 1 + + + TJTIE + TJTIE + 3 + 1 + + + ROIE + ROIE + 4 + 1 + + + TUIE + TUIE + 5 + 1 + + + RIE + RIE + 6 + 1 + + + RBUIE + RBUIE + 7 + 1 + + + RPSIE + RPSIE + 8 + 1 + + + RWTIE + RWTIE + 9 + 1 + + + ETIE + ETIE + 10 + 1 + + + FBEIE + FBEIE + 13 + 1 + + + ERIE + ERIE + 14 + 1 + + + AISE + AISE + 15 + 1 + + + NISE + NISE + 16 + 1 + + + + + DMAMFBOCR + DMAMFBOCR + Ethernet DMA missed frame and buffer + overflow counter register + 0x20 + 0x20 + read-write + 0x00000000 + + + MFC + MFC + 0 + 16 + + + OMFC + OMFC + 16 + 1 + + + MFA + MFA + 17 + 11 + + + OFOC + OFOC + 28 + 1 + + + + + DMARSWTR + DMARSWTR + Ethernet DMA receive status watchdog timer + register + 0x24 + 0x20 + read-write + 0x00000000 + + + RSWTC + RSWTC + 0 + 8 + + + + + DMACHTDR + DMACHTDR + Ethernet DMA current host transmit + descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + HTDAP + 0 + 32 + + + + + DMACHRDR + DMACHRDR + Ethernet DMA current host receive descriptor + register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + HRDAP + 0 + 32 + + + + + DMACHTBAR + DMACHTBAR + Ethernet DMA current host transmit buffer + address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + HTBAP + 0 + 32 + + + + + DMACHRBAR + DMACHRBAR + Ethernet DMA current host receive buffer + address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + HRBAP + 0 + 32 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + FS_GOTGCTL + FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + FS_GOTGINT + FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + FS_GAHBCFG + FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + FS_GUSBCFG + FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + FS_GRSTCTL + FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + FS_GINTSTS + FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + FS_GINTMSK + FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + FS_GRXSTSR_Device + FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXSTSR_Host + FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXFSIZ + FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + FS_GNPTXFSIZ_Device + FS_GNPTXFSIZ_Device + OTG_FS non-periodic transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + FS_GNPTXFSIZ_Host + FS_GNPTXFSIZ_Host + OTG_FS non-periodic transmit FIFO size + register (Host mode) + FS_GNPTXFSIZ_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + FS_GNPTXSTS + FS_GNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + FS_GCCFG + FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + + + FS_CID + FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + FS_HPTXFSIZ + FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF1 + FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF2 + FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF3 + FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + + FS_HCFG + FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + FS_HFNUM + FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + FS_HPTXSTS + FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + FS_HPRT + FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + FS_HCCHAR0 + FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR1 + FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR2 + FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR3 + FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR4 + FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR5 + FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR6 + FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR7 + FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCINT0 + FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT1 + FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT2 + FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT3 + FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT4 + FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT5 + FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT6 + FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT7 + FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINTMSK0 + FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK1 + FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK2 + FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK3 + FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK4 + FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK5 + FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK6 + FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK7 + FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCTSIZ0 + FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ1 + FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ2 + FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ3 + FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ4 + FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ5 + FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ6 + FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ7 + FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + FS_DCFG + FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + FS_DCTL + FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + FS_DSTS + FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + FS_DIEPMSK + FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + FS_DOEPMSK + FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + FS_DAINT + FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + FS_DAINTMSK + FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DVBUSDIS + DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + DVBUSPULSE + DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + FS_DIEPCTL0 + FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + DOEPCTL1 + DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPINT0 + DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT1 + DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT2 + DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT3 + DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DOEPINT0 + DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT1 + DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT2 + DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT3 + DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DTXFSTS0 + DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + + FS_PCGCCTL + FS_PCGCCTL + OTG_FS power and clock gating control + register (OTG_FS_PCGCCTL) + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2SB + 8 + 6 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + 0x00000000 + + + LATENCY + Latency + 0 + 3 + read-write + + + PRFTEN + Prefetch enable + 8 + 1 + read-write + + + ICEN + Instruction cache enable + 9 + 1 + read-write + + + DCEN + Data cache enable + 10 + 1 + read-write + + + ICRST + Instruction cache reset + 11 + 1 + write-only + + + DCRST + Data cache reset + 12 + 1 + read-write + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + PGSERR + Programming sequence error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase of sectors 0 to + 11 + 2 + 1 + + + SNB + Sector number + 3 + 5 + + + PSIZE + Program size + 8 + 2 + + + MER1 + Mass Erase of sectors 12 to + 23 + 15 + 1 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x0FFFAAED + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WDG_SW + WDG_SW User option bytes + 5 + 1 + + + nRST_STOP + nRST_STOP User option + bytes + 6 + 1 + + + nRST_STDBY + nRST_STDBY User option + bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 12 + + + + + OPTCR1 + OPTCR1 + Flash option control register + 1 + 0x18 + 0x20 + read-write + 0x0FFF0000 + + + nWRP + Not write protect + 16 + 12 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + OTG_HS_EP1_OUT + USB On The Go HS End Point 1 Out global + interrupt + 74 + + + OTG_HS_EP1_IN + USB On The Go HS End Point 1 In global + interrupt + 75 + + + OTG_HS_WKUP + USB On The Go HS Wakeup through EXTI + interrupt + 76 + + + OTG_HS + USB On The Go HS global + interrupt + 77 + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + DMAREQ + DMA request signal + 30 + 1 + read-only + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_GNPTXFSIZ_Host + OTG_HS_GNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_TX0FSIZ_Peripheral + OTG_HS_TX0FSIZ_Peripheral + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_GNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + I2CPADEN + Enable I2C bus connection for the + external I2C PHY interface + 17 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + NOVBUSSENS + VBUS sensing disable + option + 21 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Peripheral + OTG_HS_GRXSTSR_Peripheral + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Peripheral + OTG_HS_GRXSTSP_Peripheral + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPEACHMSK1 + OTG_HS_DIEPEACHMSK1 + OTG_HS device each in endpoint-1 interrupt + register + 0x40 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + + + OTG_HS_DOEPEACHMSK1 + OTG_HS_DOEPEACHMSK1 + OTG_HS device each OUT endpoint-1 interrupt + register + 0x80 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + OUT packet error mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + BERRM + Bubble error interrupt + mask + 12 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + NYETM + NYET interrupt mask + 14 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-1 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-2 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-3 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-4 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-5 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + FMC + Flexible memory controller + FSMC + 0xA0000000 + + 0x0 + 0x400 + registers + + + FMC + FSMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + CPSIZE + CPSIZE + 16 + 3 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + CPSIZE + CPSIZE + 16 + 3 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + CPSIZE + CPSIZE + 16 + 3 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + CPSIZE + CPSIZE + 16 + 3 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR2 + PCR2 + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR2 + SR2 + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM2 + PMEM2 + Common memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT2 + PATT2 + Attribute memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR2 + ECCR2 + ECC result register 2 + 0x74 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR3 + PCR3 + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR3 + SR3 + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM3 + PMEM3 + Common memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT3 + PATT3 + Attribute memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR3 + ECCR3 + ECC result register 3 + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR4 + PCR4 + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR4 + SR4 + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM4 + PMEM4 + Common memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT4 + PATT4 + Attribute memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + PIO4 + PIO4 + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IOHIZx + IOHIZx + 24 + 8 + + + IOHOLDx + IOHOLDx + 16 + 8 + + + IOWAITx + IOWAITx + 8 + 8 + + + IOSETx + IOSETx + 0 + 8 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + BUSTURN + BUSTURN + 16 + 4 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + BUSTURN + BUSTURN + 16 + 4 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + BWTR1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + BUSTURN + BUSTURN + 16 + 4 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + BWTR2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + BUSTURN + BUSTURN + 16 + 4 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + SDCR1 + SDCR1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDCR2 + SDCR2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + + + SDTR1 + SDTR1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDTR2 + SDTR2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDCMR + SDCMR + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + MODE + Command mode + 0 + 3 + write-only + + + CTB2 + Command target bank 2 + 3 + 1 + write-only + + + CTB1 + Command target bank 1 + 4 + 1 + write-only + + + NRFS + Number of Auto-refresh + 5 + 4 + read-write + + + MRD + Mode Register definition + 9 + 13 + read-write + + + + + SDRTR + SDRTR + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag + 0 + 1 + write-only + + + COUNT + Refresh Timer Count + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + RE + Refresh error flag + 0 + 1 + + + MODES1 + Status Mode for Bank 1 + 1 + 2 + + + MODES2 + Status Mode for Bank 2 + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + + + I2C3 + Inter-integrated circuit + I2C + 0x40005C00 + + 0x0 + 0x400 + registers + + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SWRST + Software reset + 15 + 1 + + + ALERT + SMBus alert + 13 + 1 + + + PEC + Packet error checking + 12 + 1 + + + POS + Acknowledge/PEC Position (for data + reception) + 11 + 1 + + + ACK + Acknowledge enable + 10 + 1 + + + STOP + Stop generation + 9 + 1 + + + START + Start generation + 8 + 1 + + + NOSTRETCH + Clock stretching disable (Slave + mode) + 7 + 1 + + + ENGC + General call enable + 6 + 1 + + + ENPEC + PEC enable + 5 + 1 + + + ENARP + ARP enable + 4 + 1 + + + SMBTYPE + SMBus type + 3 + 1 + + + SMBUS + SMBus mode + 1 + 1 + + + PE + Peripheral enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + LAST + DMA last transfer + 12 + 1 + + + DMAEN + DMA requests enable + 11 + 1 + + + ITBUFEN + Buffer interrupt enable + 10 + 1 + + + ITEVTEN + Event interrupt enable + 9 + 1 + + + ITERREN + Error interrupt enable + 8 + 1 + + + FREQ + Peripheral clock frequency + 0 + 6 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + ADDMODE + Addressing mode (slave + mode) + 15 + 1 + + + ADD10 + Interface address + 8 + 2 + + + ADD7 + Interface address + 1 + 7 + + + ADD0 + Interface address + 0 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x0000 + + + ADD2 + Interface address + 1 + 7 + + + ENDUAL + Dual addressing mode + enable + 0 + 1 + + + + + DR + DR + Data register + 0x10 + 0x20 + read-write + 0x0000 + + + DR + 8-bit data register + 0 + 8 + + + + + SR1 + SR1 + Status register 1 + 0x14 + 0x20 + 0x0000 + + + SMBALERT + SMBus alert + 15 + 1 + read-write + + + TIMEOUT + Timeout or Tlow error + 14 + 1 + read-write + + + PECERR + PEC Error in reception + 12 + 1 + read-write + + + OVR + Overrun/Underrun + 11 + 1 + read-write + + + AF + Acknowledge failure + 10 + 1 + read-write + + + ARLO + Arbitration lost (master + mode) + 9 + 1 + read-write + + + BERR + Bus error + 8 + 1 + read-write + + + TxE + Data register empty + (transmitters) + 7 + 1 + read-only + + + RxNE + Data register not empty + (receivers) + 6 + 1 + read-only + + + STOPF + Stop detection (slave + mode) + 4 + 1 + read-only + + + ADD10 + 10-bit header sent (Master + mode) + 3 + 1 + read-only + + + BTF + Byte transfer finished + 2 + 1 + read-only + + + ADDR + Address sent (master mode)/matched + (slave mode) + 1 + 1 + read-only + + + SB + Start bit (Master mode) + 0 + 1 + read-only + + + + + SR2 + SR2 + Status register 2 + 0x18 + 0x20 + read-only + 0x0000 + + + PEC + acket error checking + register + 8 + 8 + + + DUALF + Dual flag (Slave mode) + 7 + 1 + + + SMBHOST + SMBus host header (Slave + mode) + 6 + 1 + + + SMBDEFAULT + SMBus device default address (Slave + mode) + 5 + 1 + + + GENCALL + General call address (Slave + mode) + 4 + 1 + + + TRA + Transmitter/receiver + 2 + 1 + + + BUSY + Bus busy + 1 + 1 + + + MSL + Master/slave + 0 + 1 + + + + + CCR + CCR + Clock control register + 0x1C + 0x20 + read-write + 0x0000 + + + F_S + I2C master mode selection + 15 + 1 + + + DUTY + Fast mode duty cycle + 14 + 1 + + + CCR + Clock control register in Fast/Standard + mode (Master mode) + 0 + 12 + + + + + TRISE + TRISE + TRISE register + 0x20 + 0x20 + read-write + 0x0002 + + + TRISE + Maximum rise time in Fast/Standard mode + (Master mode) + 0 + 6 + + + + + FLTR + FLTR + I2C FLTR register + 0x24 + 0x20 + read-write + 0x0000 + + + DNF + Digital noise filter + 0 + 4 + + + ANOFF + Analog noise filter OFF + 4 + 1 + + + + + + + I2C2 + 0x40005800 + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2C1 + 0x40005400 + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + PVD + PVD through EXTI line detection + interrupt + 1 + + + + CR + CR + power control register + 0x0 + 0x20 + read-write + 0x0000C000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CWUF + Clear wakeup flag + 2 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + LPLVDS + Low-Power Regulator Low Voltage in + deepsleep + 10 + 1 + + + MRLVDS + Main regulator low voltage in deepsleep + mode + 11 + 1 + + + ADCDC1 + Main regulator low voltage in deepsleep + mode + 13 + 1 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ODEN + Over-drive enable + 16 + 1 + + + ODSWEN + Over-drive switching + enabled + 17 + 1 + + + UDEN + Under-drive enable in stop + mode + 18 + 2 + + + + + CSR + CSR + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUF + Wakeup flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + EWUP + Enable WKUP pin + 8 + 1 + read-write + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + ODRDY + Over-drive mode ready + 16 + 1 + read-only + + + ODSWRDY + Over-drive mode switching + ready + 17 + 1 + read-only + + + UDRDY + Under-drive ready flag + 18 + 2 + read-write + + + + + + + SAI1 + Serial audio interface + SAI + 0x40015800 + + 0x0 + 0x400 + registers + + + + BCR1 + BCR1 + BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIBEN + Audio block B enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + BCR2 + BCR2 + BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + BFRCR + BFRCR + BFRCR + 0x2C + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + BSLOTR + BSLOTR + BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + BIM + BIM + BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + BSR + BSR + BStatus register + 0x38 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + BCLRFR + BCLRFR + BClear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + BDR + BDR + BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + ACR1 + ACR1 + AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIAEN + Audio block A enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + ACR2 + ACR2 + AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + AFRCR + AFRCR + AFRCR + 0xC + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + ASLOTR + ASLOTR + ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + AIM + AIM + AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + LFSDET + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + ASR + ASR + AStatus register + 0x18 + 0x20 + read-write + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + ACLRFR + ACLRFR + AClear flag register + 0x1C + 0x20 + read-write + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + ADR + ADR + AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + + + LTDC + LCD-TFT Controller + LTDC + 0x40016800 + + 0x0 + 0x400 + registers + + + LCD_TFT + LTDC global interrupt + 88 + + + LCD_TFT_1 + LTDC global error interrupt + 89 + + + + SSCR + SSCR + Synchronization Size Configuration + Register + 0x8 + 0x20 + read-write + 0x00000000 + + + HSW + Horizontal Synchronization Width (in + units of pixel clock period) + 16 + 10 + + + VSH + Vertical Synchronization Height (in + units of horizontal scan line) + 0 + 11 + + + + + BPCR + BPCR + Back Porch Configuration + Register + 0xC + 0x20 + read-write + 0x00000000 + + + AHBP + Accumulated Horizontal back porch (in + units of pixel clock period) + 16 + 10 + + + AVBP + Accumulated Vertical back porch (in + units of horizontal scan line) + 0 + 11 + + + + + AWCR + AWCR + Active Width Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + AAV + AAV + 16 + 10 + + + AAH + Accumulated Active Height (in units of + horizontal scan line) + 0 + 11 + + + + + TWCR + TWCR + Total Width Configuration + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTALW + Total Width (in units of pixel clock + period) + 16 + 10 + + + TOTALH + Total Height (in units of horizontal + scan line) + 0 + 11 + + + + + GCR + GCR + Global Control Register + 0x18 + 0x20 + 0x00002220 + + + HSPOL + Horizontal Synchronization + Polarity + 31 + 1 + read-write + + + VSPOL + Vertical Synchronization + Polarity + 30 + 1 + read-write + + + DEPOL + Data Enable Polarity + 29 + 1 + read-write + + + PCPOL + Pixel Clock Polarity + 28 + 1 + read-write + + + DEN + Dither Enable + 16 + 1 + read-write + + + DRW + Dither Red Width + 12 + 3 + read-only + + + DGW + Dither Green Width + 8 + 3 + read-only + + + DBW + Dither Blue Width + 4 + 3 + read-only + + + LTDCEN + LCD-TFT controller enable + bit + 0 + 1 + read-write + + + + + SRCR + SRCR + Shadow Reload Configuration + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + VBR + Vertical Blanking Reload + 1 + 1 + + + IMR + Immediate Reload + 0 + 1 + + + + + BCCR + BCCR + Background Color Configuration + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BC + Background Color Red value + 0 + 24 + + + + + IER + IER + Interrupt Enable Register + 0x34 + 0x20 + read-write + 0x00000000 + + + RRIE + Register Reload interrupt + enable + 3 + 1 + + + TERRIE + Transfer Error Interrupt + Enable + 2 + 1 + + + FUIE + FIFO Underrun Interrupt + Enable + 1 + 1 + + + LIE + Line Interrupt Enable + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x38 + 0x20 + read-only + 0x00000000 + + + RRIF + Register Reload Interrupt + Flag + 3 + 1 + + + TERRIF + Transfer Error interrupt + flag + 2 + 1 + + + FUIF + FIFO Underrun Interrupt + flag + 1 + 1 + + + LIF + Line Interrupt flag + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x3C + 0x20 + write-only + 0x00000000 + + + CRRIF + Clears Register Reload Interrupt + Flag + 3 + 1 + + + CTERRIF + Clears the Transfer Error Interrupt + Flag + 2 + 1 + + + CFUIF + Clears the FIFO Underrun Interrupt + flag + 1 + 1 + + + CLIF + Clears the Line Interrupt + Flag + 0 + 1 + + + + + LIPCR + LIPCR + Line Interrupt Position Configuration + Register + 0x40 + 0x20 + read-write + 0x00000000 + + + LIPOS + Line Interrupt Position + 0 + 11 + + + + + CPSR + CPSR + Current Position Status + Register + 0x44 + 0x20 + read-only + 0x00000000 + + + CXPOS + Current X Position + 16 + 16 + + + CYPOS + Current Y Position + 0 + 16 + + + + + CDSR + CDSR + Current Display Status + Register + 0x48 + 0x20 + read-only + 0x0000000F + + + HSYNCS + Horizontal Synchronization display + Status + 3 + 1 + + + VSYNCS + Vertical Synchronization display + Status + 2 + 1 + + + HDES + Horizontal Data Enable display + Status + 1 + 1 + + + VDES + Vertical Data Enable display + Status + 0 + 1 + + + + + L1CR + L1CR + Layerx Control Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L1WHPCR + L1WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x88 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L1WVPCR + L1WVPCR + Layerx Window Vertical Position + Configuration Register + 0x8C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L1CKCR + L1CKCR + Layerx Color Keying Configuration + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L1PFCR + L1PFCR + Layerx Pixel Format Configuration + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L1CACR + L1CACR + Layerx Constant Alpha Configuration + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L1DCCR + L1DCCR + Layerx Default Color Configuration + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L1BFCR + L1BFCR + Layerx Blending Factors Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L1CFBAR + L1CFBAR + Layerx Color Frame Buffer Address + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L1CFBLR + L1CFBLR + Layerx Color Frame Buffer Length + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L1CFBLNR + L1CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L1CLUTWR + L1CLUTWR + Layerx CLUT Write Register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + L2CR + L2CR + Layerx Control Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L2WHPCR + L2WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x108 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L2WVPCR + L2WVPCR + Layerx Window Vertical Position + Configuration Register + 0x10C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L2CKCR + L2CKCR + Layerx Color Keying Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 15 + 9 + + + CKGREEN + Color Key Green value + 8 + 7 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L2PFCR + L2PFCR + Layerx Pixel Format Configuration + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L2CACR + L2CACR + Layerx Constant Alpha Configuration + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L2DCCR + L2DCCR + Layerx Default Color Configuration + Register + 0x11C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L2BFCR + L2BFCR + Layerx Blending Factors Configuration + Register + 0x120 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L2CFBAR + L2CFBAR + Layerx Color Frame Buffer Address + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L2CFBLR + L2CFBLR + Layerx Color Frame Buffer Length + Register + 0x130 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L2CFBLNR + L2CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0x134 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L2CLUTWR + L2CLUTWR + Layerx CLUT Write Register + 0x144 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + + + DMA2D + DMA2D + DMA2D + 0x4002B000 + + 0x0 + 0xC00 + registers + + + + DMA2D_CR + DMA2D_CR + DMA2D control register + 0x0 + 0x20 + read-write + 0x00000000 + + + START + Start This bit can be used to launch the + DMA2D according to the parameters loaded in the + various configuration registers. This bit is + automatically reset by the following events: ** At + the end of the transfer ** When the data transfer is + aborted by the user application by setting the ABORT + bit in DMA2D_CR ** When a data transfer error occurs + ** When the data transfer has not started due to a + configuration error or another transfer operation + already ongoing (automatic CLUT + loading). + 0 + 1 + + + SUSP + Suspend This bit can be used to suspend + the current transfer. This bit is set and reset by + software. It is automatically reset by hardware when + the START bit is reset. + 1 + 1 + + + ABORT + Abort This bit can be used to abort the + current transfer. This bit is set by software and is + automatically reset by hardware when the START bit is + reset. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 8 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 9 + 1 + + + TWIE + Transfer watermark interrupt enable This + bit is set and cleared by software. + 10 + 1 + + + CAEIE + CLUT access error interrupt enable This + bit is set and cleared by software. + 11 + 1 + + + CTCIE + CLUT transfer complete interrupt enable + This bit is set and cleared by + software. + 12 + 1 + + + CEIE + Configuration Error Interrupt Enable + This bit is set and cleared by + software. + 13 + 1 + + + MODE + DMA2D mode This bit is set and cleared + by software. It cannot be modified while a transfer + is ongoing. + 16 + 2 + + + + + DMA2D_ISR + DMA2D_ISR + DMA2D Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + TEIF + Transfer error interrupt flag This bit + is set when an error occurs during a DMA transfer + (data transfer or automatic CLUT + loading). + 0 + 1 + + + TCIF + Transfer complete interrupt flag This + bit is set when a DMA2D transfer operation is + complete (data transfer only). + 1 + 1 + + + TWIF + Transfer watermark interrupt flag This + bit is set when the last pixel of the watermarked + line has been transferred. + 2 + 1 + + + CAEIF + CLUT access error interrupt flag This + bit is set when the CPU accesses the CLUT while the + CLUT is being automatically copied from a system + memory to the internal DMA2D. + 3 + 1 + + + CTCIF + CLUT transfer complete interrupt flag + This bit is set when the CLUT copy from a system + memory area to the internal DMA2D memory is + complete. + 4 + 1 + + + CEIF + Configuration error interrupt flag This + bit is set when the START bit of DMA2D_CR, + DMA2DFGPFCCR or DMA2D_BGPFCCR is set and a wrong + configuration has been programmed. + 5 + 1 + + + + + DMA2D_IFCR + DMA2D_IFCR + DMA2D interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTEIF + Clear Transfer error interrupt flag + Programming this bit to 1 clears the TEIF flag in the + DMA2D_ISR register + 0 + 1 + + + CTCIF + Clear transfer complete interrupt flag + Programming this bit to 1 clears the TCIF flag in the + DMA2D_ISR register + 1 + 1 + + + CTWIF + Clear transfer watermark interrupt flag + Programming this bit to 1 clears the TWIF flag in the + DMA2D_ISR register + 2 + 1 + + + CAECIF + Clear CLUT access error interrupt flag + Programming this bit to 1 clears the CAEIF flag in + the DMA2D_ISR register + 3 + 1 + + + CCTCIF + Clear CLUT transfer complete interrupt + flag Programming this bit to 1 clears the CTCIF flag + in the DMA2D_ISR register + 4 + 1 + + + CCEIF + Clear configuration error interrupt flag + Programming this bit to 1 clears the CEIF flag in the + DMA2D_ISR register + 5 + 1 + + + + + DMA2D_FGMAR + DMA2D_FGMAR + DMA2D foreground memory address + register + 0xC + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the foreground image. This register can only be + written when data transfers are disabled. Once the + data transfer has started, this register is + read-only. The address alignment must match the image + format selected e.g. a 32-bit per pixel format must + be 32-bit aligned, a 16-bit per pixel format must be + 16-bit aligned and a 4-bit per pixel format must be + 8-bit aligned. + 0 + 32 + + + + + DMA2D_FGOR + DMA2D_FGOR + DMA2D foreground offset + register + 0x10 + 0x20 + read-write + 0x00000000 + + + LO + Line offset Line offset used for the + foreground expressed in pixel. This value is used to + generate the address. It is added at the end of each + line to determine the starting address of the next + line. These bits can only be written when data + transfers are disabled. Once a data transfer has + started, they become read-only. If the image format + is 4-bit per pixel, the line offset must be + even. + 0 + 14 + + + + + DMA2D_BGMAR + DMA2D_BGMAR + DMA2D background memory address + register + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the background image. This register can only be + written when data transfers are disabled. Once a data + transfer has started, this register is read-only. The + address alignment must match the image format + selected e.g. a 32-bit per pixel format must be + 32-bit aligned, a 16-bit per pixel format must be + 16-bit aligned and a 4-bit per pixel format must be + 8-bit aligned. + 0 + 32 + + + + + DMA2D_BGOR + DMA2D_BGOR + DMA2D background offset + register + 0x18 + 0x20 + read-write + 0x00000000 + + + LO + Line offset Line offset used for the + background image (expressed in pixel). This value is + used for the address generation. It is added at the + end of each line to determine the starting address of + the next line. These bits can only be written when + data transfers are disabled. Once data transfer has + started, they become read-only. If the image format + is 4-bit per pixel, the line offset must be + even. + 0 + 14 + + + + + DMA2D_FGPFCCR + DMA2D_FGPFCCR + DMA2D foreground PFC control + register + 0x1C + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits defines the color + format of the foreground image. They can only be + written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 4 + + + CCM + CLUT color mode This bit defines the + color format of the CLUT. It can only be written when + the transfer is disabled. Once the CLUT transfer has + started, this bit is read-only. + 4 + 1 + + + START + Start This bit can be set to start the + automatic loading of the CLUT. It is automatically + reset: ** at the end of the transfer ** when the + transfer is aborted by the user application by + setting the ABORT bit in DMA2D_CR ** when a transfer + error occurs ** when the transfer has not started due + to a configuration error or another transfer + operation already ongoing (data transfer or automatic + background CLUT transfer). + 5 + 1 + + + CS + CLUT size These bits define the size of + the CLUT used for the foreground image. Once the CLUT + transfer has started, this field is read-only. The + number of CLUT entries is equal to CS[7:0] + + 1. + 8 + 8 + + + AM + Alpha mode These bits select the alpha + channel value to be used for the foreground image. + They can only be written data the transfer are + disabled. Once the transfer has started, they become + read-only. other configurations are + meaningless + 16 + 2 + + + CSS + Chroma Sub-Sampling These bits define + the chroma sub-sampling mode for YCbCr color mode. + Once the transfer has started, these bits are + read-only. others: meaningless + 18 + 2 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + ALPHA + Alpha value These bits define a fixed + alpha channel value which can replace the original + alpha value or be multiplied by the original alpha + value according to the alpha mode selected through + the AM[1:0] bits. These bits can only be written when + data transfers are disabled. Once a transfer has + started, they become read-only. + 24 + 8 + + + + + DMA2D_FGCOLR + DMA2D_FGCOLR + DMA2D foreground color + register + 0x20 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits defines the blue + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, They are + read-only. + 0 + 8 + + + GREEN + Green Value These bits defines the green + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, They are + read-only. + 8 + 8 + + + RED + Red Value These bits defines the red + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 16 + 8 + + + + + DMA2D_BGPFCCR + DMA2D_BGPFCCR + DMA2D background PFC control + register + 0x24 + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits define the color + format of the foreground image. These bits can only + be written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 4 + + + CCM + CLUT Color mode These bits define the + color format of the CLUT. This register can only be + written when the transfer is disabled. Once the CLUT + transfer has started, this bit is + read-only. + 4 + 1 + + + START + Start This bit is set to start the + automatic loading of the CLUT. This bit is + automatically reset: ** at the end of the transfer ** + when the transfer is aborted by the user application + by setting the ABORT bit in the DMA2D_CR ** when a + transfer error occurs ** when the transfer has not + started due to a configuration error or another + transfer operation already on going (data transfer or + automatic BackGround CLUT transfer). + 5 + 1 + + + CS + CLUT size These bits define the size of + the CLUT used for the BG. Once the CLUT transfer has + started, this field is read-only. The number of CLUT + entries is equal to CS[7:0] + 1. + 8 + 8 + + + AM + Alpha mode These bits define which alpha + channel value to be used for the background image. + These bits can only be written when data transfers + are disabled. Once the transfer has started, they are + read-only. others: meaningless + 16 + 2 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + ALPHA + Alpha value These bits define a fixed + alpha channel value which can replace the original + alpha value or be multiplied with the original alpha + value according to the alpha mode selected with bits + AM[1: 0]. These bits can only be written when data + transfers are disabled. Once the transfer has + started, they are read-only. + 24 + 8 + + + + + DMA2D_BGCOLR + DMA2D_BGCOLR + DMA2D background color + register + 0x28 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits define the blue + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 0 + 8 + + + GREEN + Green Value These bits define the green + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 8 + 8 + + + RED + Red Value These bits define the red + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 16 + 8 + + + + + DMA2D_FGCMAR + DMA2D_FGCMAR + DMA2D foreground CLUT memory address + register + 0x2C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address Address of the data used + for the CLUT address dedicated to the foreground + image. This register can only be written when no + transfer is ongoing. Once the CLUT transfer has + started, this register is read-only. If the + foreground CLUT format is 32-bit, the address must be + 32-bit aligned. + 0 + 32 + + + + + DMA2D_BGCMAR + DMA2D_BGCMAR + DMA2D background CLUT memory address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the CLUT address dedicated to the background + image. This register can only be written when no + transfer is on going. Once the CLUT transfer has + started, this register is read-only. If the + background CLUT format is 32-bit, the address must be + 32-bit aligned. + 0 + 32 + + + + + DMA2D_OPFCCR + DMA2D_OPFCCR + DMA2D output PFC control + register + 0x34 + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits define the color + format of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 3 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + + + DMA2D_OCOLR + DMA2D_OCOLR + DMA2D output color register + 0x38 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits define the blue + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 0 + 8 + + + GREEN + Green Value These bits define the green + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 8 + 8 + + + RED + Red Value These bits define the red + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 16 + 8 + + + ALPHA + Alpha Channel Value These bits define + the alpha channel of the output color. These bits can + only be written when data transfers are disabled. + Once the transfer has started, they are + read-only. + 24 + 8 + + + + + DMA2D_OMAR + DMA2D_OMAR + DMA2D output memory address + register + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address Address of the data used + for the output FIFO. These bits can only be written + when data transfers are disabled. Once the transfer + has started, they are read-only. The address + alignment must match the image format selected e.g. a + 32-bit per pixel format must be 32-bit aligned and a + 16-bit per pixel format must be 16-bit + aligned. + 0 + 32 + + + + + DMA2D_OOR + DMA2D_OOR + DMA2D output offset register + 0x40 + 0x20 + read-write + 0x00000000 + + + LO + Line Offset Line offset used for the + output (expressed in pixels). This value is used for + the address generation. It is added at the end of + each line to determine the starting address of the + next line. These bits can only be written when data + transfers are disabled. Once the transfer has + started, they are read-only. + 0 + 14 + + + + + DMA2D_NLR + DMA2D_NLR + DMA2D number of line register + 0x44 + 0x20 + read-write + 0x00000000 + + + NL + Number of lines Number of lines of the + area to be transferred. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 0 + 16 + + + PL + Pixel per lines Number of pixels per + lines of the area to be transferred. These bits can + only be written when data transfers are disabled. + Once the transfer has started, they are read-only. If + any of the input image format is 4-bit per pixel, + pixel per lines must be even. + 16 + 14 + + + + + DMA2D_LWR + DMA2D_LWR + DMA2D line watermark register + 0x48 + 0x20 + read-write + 0x00000000 + + + LW + Line watermark These bits allow to + configure the line watermark for interrupt + generation. An interrupt is raised when the last + pixel of the watermarked line has been transferred. + These bits can only be written when data transfers + are disabled. Once the transfer has started, they are + read-only. + 0 + 16 + + + + + DMA2D_AMTCR + DMA2D_AMTCR + DMA2D AXI master timer configuration + register + 0x4C + 0x20 + read-write + 0x00000000 + + + EN + Enable Enables the dead time + functionality. + 0 + 1 + + + DT + Dead Time Dead time value in the AXI + clock cycle inserted between two consecutive accesses + on the AXI master port. These bits represent the + minimum guaranteed number of cycles between two + consecutive AXI accesses. + 8 + 8 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + FPU + Floating point interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CTRL + CTRL + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + LOAD + LOAD + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + VAL + VAL + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + Instruction access violation + flag + 1 + 1 + + + MUNSTKERR + Memory manager fault on unstacking for a + return from exception + 3 + 1 + + + MSTKERR + Memory manager fault on stacking for + exception entry. + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + Memory Management Fault Address Register + (MMAR) valid flag + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + MMFAR + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + BFAR + Bus fault address + 0 + 32 + + + + + AFSR + AFSR + Auxiliary fault status + register + 0x3C + 0x20 + read-write + 0x00000000 + + + IMPDEF + Implementation defined + 0 + 32 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISMCYCINT + DISMCYCINT + 0 + 1 + + + DISDEFWBUF + DISDEFWBUF + 1 + 1 + + + DISFOLD + DISFOLD + 2 + 1 + + + DISFPCA + DISFPCA + 8 + 1 + + + DISOOFP + DISOOFP + 9 + 1 + + + + + + + diff --git a/dev/svd/STM32F446.svd b/dev/svd/STM32F446.svd new file mode 100644 index 00000000000..3312df81be8 --- /dev/null +++ b/dev/svd/STM32F446.svd @@ -0,0 +1,57155 @@ + + + STM32F446 + 1.1 + STM32F446 + + + CM4 + r1p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + DCMI + Digital camera interface + DCMI + 0x50050000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + 0x0000 + + + CAPTURE + Capture enable + 0 + 1 + read-only + + + CM + Capture mode + 1 + 1 + read-write + + + CROP + Crop feature + 2 + 1 + read-write + + + JPEG + JPEG format + 3 + 1 + read-write + + + ESS + Embedded synchronization + select + 4 + 1 + read-write + + + PCKPOL + Pixel clock polarity + 5 + 1 + read-write + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + read-write + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + read-write + + + EDM + Extended data mode + 10 + 2 + read-write + + + ENABLE + DCMI enable + 14 + 1 + read-write + + + BSM + Byte Select mode + 16 + 2 + read-only + + + OEBS + Odd/Even Byte Select + 18 + 1 + read-only + + + LSM + Line Select mode + 19 + 1 + read-only + + + OELS + Odd/Even Line Select + 20 + 1 + read-only + + + FCRC + Frame capture rate control + 8 + 2 + read-write + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + FMC + Flexible memory controller + FSMC + 0xA0000000 + + 0x0 + 0x400 + registers + + + FMC + FMC global interrupt + 48 + + + FMC + FMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR2 + PCR2 + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR2 + SR2 + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM2 + PMEM2 + Common memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT2 + PATT2 + Attribute memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR2 + ECCR2 + ECC result register 2 + 0x74 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR3 + PCR3 + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR3 + SR3 + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM3 + PMEM3 + Common memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT3 + PATT3 + Attribute memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR3 + ECCR3 + ECC result register 3 + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + PCR4 + PCR4 + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR4 + SR4 + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM4 + PMEM4 + Common memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT4 + PATT4 + Attribute memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + PIO4 + PIO4 + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IOHIZx + IOHIZx + 24 + 8 + + + IOHOLDx + IOHOLDx + 16 + 8 + + + IOWAITx + IOWAITx + 8 + 8 + + + IOSETx + IOSETx + 0 + 8 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + SDCR1 + SDCR1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDCR2 + SDCR2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDTR1 + SDTR1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDTR2 + SDTR2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDCMR + SDCMR + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + MODE + Command mode + 0 + 3 + write-only + + + CTB2 + Command target bank 2 + 3 + 1 + write-only + + + CTB1 + Command target bank 1 + 4 + 1 + write-only + + + NRFS + Number of Auto-refresh + 5 + 4 + read-write + + + MRD + Mode Register definition + 9 + 13 + read-write + + + + + SDRTR + SDRTR + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag + 0 + 1 + write-only + + + COUNT + Refresh Timer Count + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + RE + Refresh error flag + 0 + 1 + + + MODES1 + Status Mode for Bank 1 + 1 + 2 + + + MODES2 + Status Mode for Bank 2 + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_RTC_STOP + RTC stopped when Core is + halted + 10 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_I2CFMP_SMBUS_TIMEOUT + SMBUS timeout mode stopped when Core is + halted + 24 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLSAIRDYC + PLLSAI Ready Interrupt + Clear + 22 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLSAIRDYIE + PLLSAI Ready Interrupt + Enable + 14 + 1 + read-write + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLSAIRDYF + PLLSAI ready interrupt + flag + 6 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + DCMIRST + Camera interface reset + 0 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FMCRST + Flexible memory controller module + reset + 0 + 1 + + + QSPIRST + QUADSPI module reset + 1 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM2 reset + 0 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + SPDIFRST + SPDIF-IN reset + 16 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + I2CFMP1RST + I2CFMP1 reset + 24 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 reset + 0 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + SDIORST + SDIO reset + 11 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM11RST + TIM11 reset + 18 + 1 + + + SAI1RST + SAI1 reset + 22 + 1 + + + SAI2RST + SAI2 reset + 23 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + DCMIEN + Camera interface enable + 0 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FMCEN + Flexible memory controller module clock + enable + 0 + 1 + + + QSPIEN + QUADSPI memory controller module clock + enable + 1 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + SPDIFEN + SPDIF-IN clock enable + 16 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + I2CFMP1EN + I2CFMP1 clock enable + 24 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + CAN2EN + CAN 2 clock enable + 26 + 1 + + + CEC + CEC interface clock enable + 27 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SDIOEN + SDIO clock enable + 11 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4ENR + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + SAI1EN + SAI1 clock enable + 22 + 1 + + + SAI2EN + SAI2 clock enable + 23 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + DCMILPEN + Camera interface enable during Sleep + mode + 0 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FMCLPEN + Flexible memory controller module clock + enable during Sleep mode + 0 + 1 + + + QSPILPEN + QUADSPI memory controller module clock + enable during Sleep mode + 1 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + SPDIFLPEN + SPDIF clock enable during Sleep + mode + 16 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + I2CFMP1LPEN + I2CFMP1 clock enable during Sleep + mode + 24 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + CECLPEN + CEC clock enable during Sleep + mode + 27 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + SDIOLPEN + SDIO clock enable during Sleep + mode + 11 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI 4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + SAI1LPEN + SAI1 clock enable + 22 + 1 + + + SAI2LPEN + SAI2 clock enable + 23 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL + RTC clock source selection + 8 + 2 + read-write + + + LSEMOD + External low-speed oscillator + mode + 3 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SM + Division factor for audio PLL (PLLI2S) + input clock + 0 + 6 + + + PLLI2SN + PLLI2S multiplication factor for + VCO + 6 + 9 + + + PLLI2SP + PLLI2S division factor for SPDIF-IN + clock + 16 + 2 + + + PLLI2SQ + PLLI2S division factor for SAI1 + clock + 24 + 4 + + + PLLI2SR + PLLI2S division factor for I2S + clocks + 28 + 3 + + + + + PLLSAICFGR + PLLSAICFGR + PLL configuration register + 0x88 + 0x20 + read-write + 0x24003000 + + + PLLSAIM + Division factor for audio PLLSAI input + clock + 0 + 6 + + + PLLSAIN + PLLSAI division factor for + VCO + 6 + 9 + + + PLLSAIP + PLLSAI division factor for 48 MHz + clock + 16 + 2 + + + PLLSAIQ + PLLSAI division factor for SAIs + clock + 24 + 4 + + + + + DCKCFGR + DCKCFGR + Dedicated Clock Configuration + Register + 0x8C + 0x20 + read-write + 0x00000000 + + + PLLI2SDIVQ + PLLI2S division factor for SAIs + clock + 0 + 5 + + + PLLSAIDIVQ + PLLSAI division factor for SAIs + clock + 8 + 5 + + + SAI1SRC + SAI1 clock source + selection + 20 + 2 + + + SAI2SRC + SAI2 clock source + selection + 22 + 2 + + + TIMPRE + Timers clocks prescalers + selection + 24 + 1 + + + I2S1SRC + I2S APB1 clock source + selection + 25 + 2 + + + I2S2SRC + I2S APB2 clock source + selection + 27 + 2 + + + + + CKGATENR + CKGATENR + clocks gated enable register + 0x90 + 0x20 + read-write + 0x00000000 + + + AHB2APB1_CKEN + AHB to APB1 Bridge clock + enable + 0 + 1 + + + AHB2APB2_CKEN + AHB to APB2 Bridge clock + enable + 1 + 1 + + + CM4DBG_CKEN + Cortex M4 ETM clock enable + 2 + 1 + + + SPARE_CKEN + Spare clock enable + 3 + 1 + + + SRAM_CKEN + SRQAM controller clock + enable + 4 + 1 + + + FLITF_CKEN + Flash Interface clock + enable + 5 + 1 + + + RCC_CKEN + RCC clock enable + 6 + 1 + + + + + DCKCFGR2 + DCKCFGR2 + dedicated clocks configuration register + 2 + 0x94 + 0x20 + read-write + 0x00000000 + + + FMPI2C1SEL + I2C4 kernel clock source + selection + 22 + 2 + + + CECSEL + HDMI CEC clock source + selection + 26 + 1 + + + CK48MSEL + SDIO/USBFS/HS clock + selection + 27 + 1 + + + SDIOSEL + SDIO clock selection + 28 + 1 + + + SPDIFSEL + SPDIF clock selection + 29 + 1 + + + + + + + GPIOH + General-purpose I/Os + GPIO + 0x40021C00 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOG + 0x40021800 + + + GPIOF + 0x40021400 + + + GPIOE + 0x40021000 + + + GPIOD + 0X40020C00 + + + GPIOC + 0x40020800 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + Memory mapping selection + 0 + 3 + + + FB_MODE + Flash bank mode selection + 8 + 1 + + + SWP_FMC + FMC memory mapping swap + 10 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + Ethernet PHY interface + selection + 23 + 1 + + + ADC1DC2 + ADC1DC2 + 16 + 1 + + + ADC2DC2 + ADC2DC2 + 17 + 1 + + + ADC3DC2 + ADC3DC2 + 18 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + DFF + Data frame format + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + FRF + Frame format + 4 + 1 + + + SSOE + SS output enable + 2 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + TIFRFE + TI frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + SPI3 + SPI3 global interrupt + 51 + + + + SPI4 + 0x40013400 + + SPI4 + SPI 4 global interrupt + 84 + + + SPI4 + SPI 4 global interrupt + 84 + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x51 + registers + + + ADC + ADC1 global interrupt + 18 + + + ADC + ADC1 global interrupt + 18 + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC2 + 0x40012100 + + ADC + ADC2 global interrupts + 18 + + + ADC + ADC2 global interrupts + 18 + + + + ADC3 + 0x40012200 + + ADC + ADC3 global interrupts + 18 + + + ADC + ADC3 global interrupts + 18 + + + + USART6 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011400 + + 0x0 + 0x400 + registers + + + USART6 + USART6 global interrupt + 71 + + + USART6 + USART6 global interrupt + 71 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + CTS + CTS flag + 9 + 1 + read-write + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x18 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + + + USART1 + 0x40011000 + + USART1 + USART1 global interrupt + 37 + + + USART1 + USART1 global interrupt + 37 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + USART2 + USART2 global interrupt + 38 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + USART3 + USART3 global interrupt + 39 + + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + UART7 + UART 7 global interrupt + 82 + + + UART7 + UART 7 global interrupt + 82 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + I2C3 + Inter-integrated circuit + I2C + 0x40005C00 + + 0x0 + 0x400 + registers + + + UART8 + UART 8 global interrupt + 83 + + + UART8 + UART 8 global interrupt + 83 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SWRST + Software reset + 15 + 1 + + + ALERT + SMBus alert + 13 + 1 + + + PEC + Packet error checking + 12 + 1 + + + POS + Acknowledge/PEC Position (for data + reception) + 11 + 1 + + + ACK + Acknowledge enable + 10 + 1 + + + STOP + Stop generation + 9 + 1 + + + START + Start generation + 8 + 1 + + + NOSTRETCH + Clock stretching disable (Slave + mode) + 7 + 1 + + + ENGC + General call enable + 6 + 1 + + + ENPEC + PEC enable + 5 + 1 + + + ENARP + ARP enable + 4 + 1 + + + SMBTYPE + SMBus type + 3 + 1 + + + SMBUS + SMBus mode + 1 + 1 + + + PE + Peripheral enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + LAST + DMA last transfer + 12 + 1 + + + DMAEN + DMA requests enable + 11 + 1 + + + ITBUFEN + Buffer interrupt enable + 10 + 1 + + + ITEVTEN + Event interrupt enable + 9 + 1 + + + ITERREN + Error interrupt enable + 8 + 1 + + + FREQ + Peripheral clock frequency + 0 + 6 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + ADDMODE + Addressing mode (slave + mode) + 15 + 1 + + + ADD10 + Interface address + 8 + 2 + + + ADD7 + Interface address + 1 + 7 + + + ADD0 + Interface address + 0 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x0000 + + + ADD2 + Interface address + 1 + 7 + + + ENDUAL + Dual addressing mode + enable + 0 + 1 + + + + + DR + DR + Data register + 0x10 + 0x20 + read-write + 0x0000 + + + DR + 8-bit data register + 0 + 8 + + + + + SR1 + SR1 + Status register 1 + 0x14 + 0x20 + 0x0000 + + + SMBALERT + SMBus alert + 15 + 1 + read-write + + + TIMEOUT + Timeout or Tlow error + 14 + 1 + read-write + + + PECERR + PEC Error in reception + 12 + 1 + read-write + + + OVR + Overrun/Underrun + 11 + 1 + read-write + + + AF + Acknowledge failure + 10 + 1 + read-write + + + ARLO + Arbitration lost (master + mode) + 9 + 1 + read-write + + + BERR + Bus error + 8 + 1 + read-write + + + TxE + Data register empty + (transmitters) + 7 + 1 + read-only + + + RxNE + Data register not empty + (receivers) + 6 + 1 + read-only + + + STOPF + Stop detection (slave + mode) + 4 + 1 + read-only + + + ADD10 + 10-bit header sent (Master + mode) + 3 + 1 + read-only + + + BTF + Byte transfer finished + 2 + 1 + read-only + + + ADDR + Address sent (master mode)/matched + (slave mode) + 1 + 1 + read-only + + + SB + Start bit (Master mode) + 0 + 1 + read-only + + + + + SR2 + SR2 + Status register 2 + 0x18 + 0x20 + read-only + 0x0000 + + + PEC + acket error checking + register + 8 + 8 + + + DUALF + Dual flag (Slave mode) + 7 + 1 + + + SMBHOST + SMBus host header (Slave + mode) + 6 + 1 + + + SMBDEFAULT + SMBus device default address (Slave + mode) + 5 + 1 + + + GENCALL + General call address (Slave + mode) + 4 + 1 + + + TRA + Transmitter/receiver + 2 + 1 + + + BUSY + Bus busy + 1 + 1 + + + MSL + Master/slave + 0 + 1 + + + + + CCR + CCR + Clock control register + 0x1C + 0x20 + read-write + 0x0000 + + + F_S + I2C master mode selection + 15 + 1 + + + DUTY + Fast mode duty cycle + 14 + 1 + + + CCR + Clock control register in Fast/Standard + mode (Master mode) + 0 + 12 + + + + + TRISE + TRISE + TRISE register + 0x20 + 0x20 + read-write + 0x0002 + + + TRISE + Maximum rise time in Fast/Standard mode + (Master mode) + 0 + 6 + + + + + FLTR + FLTR + I2C FLTR register + 0x24 + 0x20 + read-write + 0x0000 + + + DNF + Digital noise filter + 0 + 4 + + + ANOFF + Analog noise filter OFF + 4 + 1 + + + + + + + I2C2 + 0x40005800 + + + I2C1 + 0x40005400 + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + COE + Calibration output enable + 23 + 1 + + + OSEL + Output selection + 21 + 2 + + + POL + Output polarity + 20 + 1 + + + BKP + Backup + 18 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + DCE + Coarse digital calibration + enable + 7 + 1 + + + FMT + Hour format + 6 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + TAMPER2 detection flag + 14 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + CALIBR + CALIBR + calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + DCS + Digital calibration sign + 7 + 1 + + + DC + Digital calibration + 0 + 5 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAFCR + TAFCR + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + ALARMOUTTYPE + AFO_ALARM output type + 18 + 1 + + + TSINSEL + TIMESTAMP mapping + 17 + 1 + + + TAMP1INSEL + TAMPER1 mapping + 16 + 1 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + UART4 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40004C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + WWDG + Window Watchdog interrupt + 0 + + + + SR + SR + Status register + 0x0 + 0x20 + 0x00C00000 + + + LBD + LIN break detection flag + 8 + 1 + read-write + + + TXE + Transmit data register + empty + 7 + 1 + read-only + + + TC + Transmission complete + 6 + 1 + read-write + + + RXNE + Read data register not + empty + 5 + 1 + read-write + + + IDLE + IDLE line detected + 4 + 1 + read-only + + + ORE + Overrun error + 3 + 1 + read-only + + + NF + Noise detected flag + 2 + 1 + read-only + + + FE + Framing error + 1 + 1 + read-only + + + PE + Parity error + 0 + 1 + read-only + + + + + DR + DR + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DR + Data value + 0 + 9 + + + + + BRR + BRR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + mantissa of USARTDIV + 4 + 12 + + + DIV_Fraction + fraction of USARTDIV + 0 + 4 + + + + + CR1 + CR1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + OVER8 + Oversampling mode + 15 + 1 + + + UE + USART enable + 13 + 1 + + + M + Word length + 12 + 1 + + + WAKE + Wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + TXE interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + RWU + Receiver wakeup + 1 + 1 + + + SBK + Send break + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + lin break detection length + 5 + 1 + + + ADD + Address of the USART node + 0 + 4 + + + + + CR3 + CR3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + IrDA low-power + 2 + 1 + + + IREN + IrDA mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + + + UART5 + 0x40005000 + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTC_WKUP + RTC Wakeup interrupt through the EXTI + line + 3 + + + RTC_Alarm + RTC Alarms (A and B) through EXTI line + interrupt + 41 + + + RTC_Alarm + RTC Alarms (A and B) through EXTI line + interrupt + 41 + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0xD + registers + + + UART4 + UART4 global interrupt + 52 + + + UART4 + UART4 global interrupt + 52 + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + UART5 + UART5 global interrupt + 53 + + + UART5 + UART5 global interrupt + 53 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + + + TIM8 + 0x40010400 + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + ITR1_RMP + Timer Input 4 remap + 10 + 2 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM4 + 0x40000800 + + TIM2 + TIM2 global interrupt + 28 + + + TIM2 + TIM2 global interrupt + 28 + + + + TIM5 + General-purpose-timers + TIM + 0x40000C00 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM5 option register + 0x50 + 0x20 + read-write + 0x0000 + + + IT4_RMP + Timer Input 4 remap + 6 + 2 + + + + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + TIM4 + TIM4 global interrupt + 30 + + + TIM4 + TIM4 global interrupt + 30 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + TIM5 + TIM5 global interrupt + 50 + + + TIM5 + TIM5 global interrupt + 50 + + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + + + TIM13 + 0x40001C00 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + + TIM14 + 0x40002000 + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 global + interrupt + 25 + + + + TIM11 + General-purpose-timers + TIM + 0x40014800 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + RMP + Input 1 remapping + capability + 0 + 2 + + + + + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + TIM7 + TIM7 global interrupt + 55 + + + TIM7 + TIM7 global interrupt + 55 + + + + FS_GOTGCTL + FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + FS_GOTGINT + FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + FS_GAHBCFG + FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + FS_GUSBCFG + FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + FS_GRSTCTL + FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + FS_GINTSTS + FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + FS_GINTMSK + FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + FS_GRXSTSR_Device + FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXSTSR_Host + FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + FS_GRXFSIZ + FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + FS_GNPTXFSIZ_Device + FS_GNPTXFSIZ_Device + OTG_FS non-periodic transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + FS_GNPTXFSIZ_Host + FS_GNPTXFSIZ_Host + OTG_FS non-periodic transmit FIFO size + register (Host mode) + FS_GNPTXFSIZ_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + FS_GNPTXSTS + FS_GNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + FS_GCCFG + FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + + + FS_CID + FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + FS_HPTXFSIZ + FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF1 + FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF2 + FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + FS_DIEPTXF3 + FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + ETH + Ethernet global interrupt + 61 + + + ETH + Ethernet global interrupt + 61 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + + FS_HCFG + FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + FS_HFNUM + FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + FS_HPTXSTS + FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + FS_HPRT + FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + FS_HCCHAR0 + FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR1 + FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR2 + FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR3 + FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR4 + FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR5 + FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR6 + FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCCHAR7 + FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + FS_HCINT0 + FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT1 + FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT2 + FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT3 + FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT4 + FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT5 + FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT6 + FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINT7 + FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + FS_HCINTMSK0 + FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK1 + FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK2 + FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK3 + FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK4 + FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK5 + FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK6 + FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCINTMSK7 + FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + FS_HCTSIZ0 + FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ1 + FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ2 + FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ3 + FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ4 + FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ5 + FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ6 + FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + FS_HCTSIZ7 + FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + FS_DCFG + FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + FS_DCTL + FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + FS_DSTS + FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + FS_DIEPMSK + FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + FS_DOEPMSK + FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + FS_DAINT + FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + FS_DAINTMSK + FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DVBUSDIS + DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + DVBUSPULSE + DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + FS_DIEPCTL0 + FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + DOEPCTL1 + DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + DIEPINT0 + DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT1 + DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT2 + DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DIEPINT3 + DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + DOEPINT0 + DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT1 + DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT2 + DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DOEPINT3 + DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DTXFSTS0 + DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + + FS_PCGCCTL + FS_PCGCCTL + OTG_FS power and clock gating control + register (OTG_FS_PCGCCTL) + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2SB + 8 + 6 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + 0x00000000 + + + LATENCY + Latency + 0 + 3 + read-write + + + PRFTEN + Prefetch enable + 8 + 1 + read-write + + + ICEN + Instruction cache enable + 9 + 1 + read-write + + + DCEN + Data cache enable + 10 + 1 + read-write + + + ICRST + Instruction cache reset + 11 + 1 + write-only + + + DCRST + Data cache reset + 12 + 1 + read-write + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + PGSERR + Programming sequence error + 7 + 1 + read-write + + + RDERR + Read Protection Error + 8 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase of sectors 0 to + 11 + 2 + 1 + + + SNB + Sector number + 3 + 4 + + + PSIZE + Program size + 8 + 2 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x0FFFAAED + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WDG_SW + WDG_SW User option bytes + 5 + 1 + + + nRST_STOP + nRST_STOP User option + bytes + 6 + 1 + + + nRST_STDBY + nRST_STDBY User option + bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 8 + + + SPRMOD + Selection of Protection Mode of nWPRi + bits + 31 + 1 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + CTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + DMAREQ + DMA request signal + 30 + 1 + read-only + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + EPMISM + Endpoint mismatch interrupt + mask + 17 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_GNPTXFSIZ_Host + OTG_HS_GNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_TX0FSIZ_Peripheral + OTG_HS_TX0FSIZ_Peripheral + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_GNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + I2CPADEN + Enable I2C bus connection for the + external I2C PHY interface + 17 + 1 + + + VBUSASEN + Enable the VBUS sensing + device + 18 + 1 + + + VBUSBSEN + Enable the VBUS sensing + device + 19 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + NOVBUSSENS + VBUS sensing disable + option + 21 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Peripheral + OTG_HS_GRXSTSR_Peripheral + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Peripheral + OTG_HS_GRXSTSP_Peripheral + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPEACHMSK1 + OTG_HS_DIEPEACHMSK1 + OTG_HS device each in endpoint-1 interrupt + register + 0x40 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + + + OTG_HS_DOEPEACHMSK1 + OTG_HS_DOEPEACHMSK1 + OTG_HS device each OUT endpoint-1 interrupt + register + 0x80 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + OUT packet error mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + BERRM + Bubble error interrupt + mask + 12 + 1 + + + NAKM + NAK interrupt mask + 13 + 1 + + + NYETM + NYET interrupt mask + 14 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-1 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-2 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-3 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-4 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-5 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + SAI1 + Serial audio interface + SAI + 0x40015800 + + 0x0 + 0x400 + registers + + + + BCR1 + BCR1 + BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIBEN + Audio block B enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + BCR2 + BCR2 + BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + BFRCR + BFRCR + BFRCR + 0x2C + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + BSLOTR + BSLOTR + BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + BIM + BIM + BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + BSR + BSR + BStatus register + 0x38 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + BCLRFR + BCLRFR + BClear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + BDR + BDR + BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + ACR1 + ACR1 + AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIAEN + Audio block A enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + ACR2 + ACR2 + AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + AFRCR + AFRCR + AFRCR + 0xC + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + ASLOTR + ASLOTR + ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + AIM + AIM + AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + LFSDET + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + ASR + ASR + AStatus register + 0x18 + 0x20 + read-write + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + ACLRFR + ACLRFR + AClear flag register + 0x1C + 0x20 + read-write + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + ADR + ADR + AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + GCR + GCR + Global configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + SYNCIN + Synchronization inputs + 0 + 2 + + + SYNCOUT + Synchronization outputs + 4 + 2 + + + + + + + SAI2 + 0x40015C00 + + FLASH + Flash global interrupt + 4 + + + FLASH + Flash global interrupt + 4 + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + CR + CR + power control register + 0x0 + 0x20 + read-write + 0x0000C000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CWUF + Clear wakeup flag + 2 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + LPLVDS + Low-Power Regulator Low Voltage in + deepsleep + 10 + 1 + + + MRLVDS + Main regulator low voltage in deepsleep + mode + 11 + 1 + + + ADCDC1 + ADCDC1 + 13 + 1 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ODEN + Over-drive enable + 16 + 1 + + + ODSWEN + Over-drive switching + enabled + 17 + 1 + + + UDEN + Under-drive enable in stop + mode + 18 + 2 + + + FMSSR + Flash Memory Stop while System + Run + 20 + 1 + + + FISSR + Flash Interface Stop while System + Run + 21 + 1 + + + + + CSR + CSR + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUF + Wakeup flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + EWUP2 + Enable WKUP2 pin + 7 + 1 + read-write + + + EWUP + Enable WKUP pin + 8 + 1 + read-write + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-only + + + ODRDY + Over-drive mode ready + 16 + 1 + read-only + + + ODSWRDY + Over-drive mode switching + ready + 17 + 1 + read-only + + + UDRDY + Under-drive ready flag + 18 + 2 + read-write + + + + + + + QUADSPI + QuadSPI interface + QUADSPI + 0xA0001000 + + 0x0 + 0x400 + registers + + + LCD_TFT + LTDC global interrupt + 88 + + + LCD_TFT + LTDC global interrupt + 88 + + + LCD_TFT_1 + LTDC global error interrupt + 89 + + + LCD_TFT_1 + LTDC global error interrupt + 89 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PRESCALER + Clock prescaler + 24 + 8 + + + PMM + Polling match mode + 23 + 1 + + + APMS + Automatic poll mode stop + 22 + 1 + + + TOIE + TimeOut interrupt enable + 20 + 1 + + + SMIE + Status match interrupt + enable + 19 + 1 + + + FTIE + FIFO threshold interrupt + enable + 18 + 1 + + + TCIE + Transfer complete interrupt + enable + 17 + 1 + + + TEIE + Transfer error interrupt + enable + 16 + 1 + + + FTHRES + IFO threshold level + 8 + 5 + + + FSEL + FLASH memory selection + 7 + 1 + + + DFM + Dual-flash mode + 6 + 1 + + + SSHIFT + Sample shift + 4 + 1 + + + TCEN + Timeout counter enable + 3 + 1 + + + DMAEN + DMA enable + 2 + 1 + + + ABORT + Abort request + 1 + 1 + + + EN + Enable + 0 + 1 + + + + + DCR + DCR + device configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + FSIZE + FLASH memory size + 16 + 5 + + + CSHT + Chip select high time + 8 + 3 + + + CKMODE + Mode 0 / mode 3 + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + read-only + 0x00000000 + + + FLEVEL + FIFO level + 8 + 7 + + + BUSY + Busy + 5 + 1 + + + TOF + Timeout flag + 4 + 1 + + + SMF + Status match flag + 3 + 1 + + + FTF + FIFO threshold flag + 2 + 1 + + + TCF + Transfer complete flag + 1 + 1 + + + TEF + Transfer error flag + 0 + 1 + + + + + FCR + FCR + flag clear register + 0xC + 0x20 + read-write + 0x00000000 + + + CTOF + Clear timeout flag + 4 + 1 + + + CSMF + Clear status match flag + 3 + 1 + + + CTCF + Clear transfer complete + flag + 1 + 1 + + + CTEF + Clear transfer error flag + 0 + 1 + + + + + DLR + DLR + data length register + 0x10 + 0x20 + read-write + 0x00000000 + + + DL + Data length + 0 + 32 + + + + + CCR + CCR + communication configuration + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DDRM + Double data rate mode + 31 + 1 + + + DHHC + DDR hold half cycle + 30 + 1 + + + SIOO + Send instruction only once + mode + 28 + 1 + + + FMODE + Functional mode + 26 + 2 + + + DMODE + Data mode + 24 + 2 + + + DCYC + Number of dummy cycles + 18 + 5 + + + ABSIZE + Alternate bytes size + 16 + 2 + + + ABMODE + Alternate bytes mode + 14 + 2 + + + ADSIZE + Address size + 12 + 2 + + + ADMODE + Address mode + 10 + 2 + + + IMODE + Instruction mode + 8 + 2 + + + INSTRUCTION + Instruction + 0 + 8 + + + + + AR + AR + address register + 0x18 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Address + 0 + 32 + + + + + ABR + ABR + ABR + 0x1C + 0x20 + read-write + 0x00000000 + + + ALTERNATE + ALTERNATE + 0 + 32 + + + + + DR + DR + data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + PSMKR + PSMKR + polling status mask register + 0x24 + 0x20 + read-write + 0x00000000 + + + MASK + Status mask + 0 + 32 + + + + + PSMAR + PSMAR + polling status match register + 0x28 + 0x20 + read-write + 0x00000000 + + + MATCH + Status match + 0 + 32 + + + + + PIR + PIR + polling interval register + 0x2C + 0x20 + read-write + 0x00000000 + + + INTERVAL + Polling interval + 0 + 16 + + + + + LPTR + LPTR + low-power timeout register + 0x30 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Timeout period + 0 + 16 + + + + + + + SPDIF_RX + Receiver Interface + SPDIF_RX + 0x40004000 + + 0x0 + 0x400 + registers + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x00000000 + + + SPDIFEN + Peripheral Block Enable + 0 + 2 + + + RXDMAEN + Receiver DMA ENable for data + flow + 2 + 1 + + + RXSTEO + STerEO Mode + 3 + 1 + + + DRFMT + RX Data format + 4 + 2 + + + PMSK + Mask Parity error bit + 6 + 1 + + + VMSK + Mask of Validity bit + 7 + 1 + + + CUMSK + Mask of channel status and user + bits + 8 + 1 + + + PTMSK + Mask of Preamble Type bits + 9 + 1 + + + CBDMAEN + Control Buffer DMA ENable for control + flow + 10 + 1 + + + CHSEL + Channel Selection + 11 + 1 + + + NBTR + Maximum allowed re-tries during + synchronization phase + 12 + 2 + + + WFA + Wait For Activity + 14 + 1 + + + INSEL + input selection + 16 + 3 + + + + + IMR + IMR + Interrupt mask register + 0x4 + 0x20 + read-write + 0x00000000 + + + RXNEIE + RXNE interrupt enable + 0 + 1 + + + CSRNEIE + Control Buffer Ready Interrupt + Enable + 1 + 1 + + + PERRIE + Parity error interrupt + enable + 2 + 1 + + + OVRIE + Overrun error Interrupt + Enable + 3 + 1 + + + SBLKIE + Synchronization Block Detected Interrupt + Enable + 4 + 1 + + + SYNCDIE + Synchronization Done + 5 + 1 + + + IFEIE + Serial Interface Error Interrupt + Enable + 6 + 1 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-only + 0x00000000 + + + RXNE + Read data register not + empty + 0 + 1 + + + CSRNE + Control Buffer register is not + empty + 1 + 1 + + + PERR + Parity error + 2 + 1 + + + OVR + Overrun error + 3 + 1 + + + SBD + Synchronization Block + Detected + 4 + 1 + + + SYNCD + Synchronization Done + 5 + 1 + + + FERR + Framing error + 6 + 1 + + + SERR + Synchronization error + 7 + 1 + + + TERR + Time-out error + 8 + 1 + + + WIDTH5 + Duration of 5 symbols counted with + SPDIF_CLK + 16 + 15 + + + + + IFCR + IFCR + Interrupt Flag Clear register + 0xC + 0x20 + write-only + 0x00000000 + + + PERRCF + Clears the Parity error + flag + 2 + 1 + + + OVRCF + Clears the Overrun error + flag + 3 + 1 + + + SBDCF + Clears the Synchronization Block + Detected flag + 4 + 1 + + + SYNCDCF + Clears the Synchronization Done + flag + 5 + 1 + + + + + DR + DR + Data input register + 0x10 + 0x20 + read-only + 0x00000000 + + + DR + Parity Error bit + 0 + 24 + + + PE + Parity Error bit + 24 + 1 + + + V + Validity bit + 25 + 1 + + + U + User bit + 26 + 1 + + + C + Channel Status bit + 27 + 1 + + + PT + Preamble Type + 28 + 2 + + + + + CSR + CSR + Channel Status register + 0x14 + 0x20 + read-only + 0x00000000 + + + USR + User data information + 0 + 16 + + + CS + Channel A status + information + 16 + 8 + + + SOB + Start Of Block + 24 + 1 + + + + + DIR + DIR + Debug Information register + 0x18 + 0x20 + read-only + 0x00000000 + + + THI + Threshold HIGH + 0 + 13 + + + TLO + Threshold LOW + 16 + 13 + + + + + + + SDMMC + SDMMC + SDMMC + 0x40012C00 + + 0x0 + 0x3FD + registers + + + + SDMMC_POWER + SDMMC_POWER + SDMMC power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + SDMMC state control bits. These bits can + only be written when the SDMMC is not in the power-on + state (PWRCTRL?11). These bits are used to define the + functional state of the SDMMC signals: Any further + write will be ignored, PWRCTRL value will keep + 11. + 0 + 2 + + + VSWITCH + Voltage switch sequence start. This bit + is used to start the timing critical section of the + voltage switch sequence: + 2 + 1 + + + VSWITCHEN + Voltage switch procedure enable. This + bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). This bit is used to stop the + SDMMC_CK after the voltage switch command + response: + 3 + 1 + + + DIRPOL + Data and command direction signals + polarity selection. This bit can only be written when + the SDMMC is in the power-off state (PWRCTRL = + 00). + 4 + 1 + + + + + SDMMC_CLKCR + SDMMC_CLKCR + The SDMMC_CLKCR register controls the + SDMMC_CK output clock, the SDMMC_RX_CLK receive clock, + and the bus width. + 0x4 + 0x20 + read-write + 0x00000000 + + + CLKDIV + Clock divide factor This bit can only be + written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0). This field defines the + divide factor between the input clock (SDMMCCLK) and + the output clock (SDMMC_CK): SDMMC_CK frequency = + SDMMCCLK / [2 * CLKDIV]. 0xx: etc.. xxx: + etc.. + 0 + 10 + + + PWRSAV + Power saving configuration bit This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) For power + saving, the SDMMC_CK clock output can be disabled + when the bus is idle by setting PWRSAV: + 12 + 1 + + + WIDBUS + Wide bus mode enable bit This bit can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 14 + 2 + + + NEGEDGE + SDMMC_CK dephasing selection bit for + data and Command. This bit can only be written when + the CPSM and DPSM are not active (CPSMACT = 0 and + DPSMACT = 0). When clock division = 1 (CLKDIV = 0), + this bit has no effect. Data and Command change on + SDMMC_CK falling edge. When clock division &gt;1 + (CLKDIV &gt; 0) &amp; DDR = 0: - SDMMC_CK + edge occurs on SDMMCCLK rising edge. When clock + division >1 (CLKDIV > 0) & DDR = 1: - Data + changed on the SDMMCCLK falling edge succeeding a + SDMMC_CK edge. - SDMMC_CK edge occurs on SDMMCCLK + rising edge. - Data changed on the SDMMC_CK falling + edge succeeding a SDMMC_CK edge. - SDMMC_CK edge + occurs on SDMMCCLK rising edge. + 16 + 1 + + + HWFC_EN + Hardware flow control enable This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) When Hardware + flow control is enabled, the meaning of the TXFIFOE + and RXFIFOF flags change, please see SDMMC status + register definition in Section56.8.11. + 17 + 1 + + + DDR + Data rate signaling selection This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) DDR rate shall + only be selected with 4-bit or 8-bit wide bus mode. + (WIDBUS &gt; 00). DDR = 1 has no effect when + WIDBUS = 00 (1-bit wide bus). DDR rate shall only be + selected with clock division &gt;1. (CLKDIV + &gt; 0) + 18 + 1 + + + BUSSPEED + Bus speed mode selection between DS, HS, + SDR12, SDR25 and SDR50, DDR50, SDR104. This bit can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 19 + 1 + + + SELCLKRX + Receive clock selection. These bits can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 20 + 2 + + + + + SDMMC_ARGR + SDMMC_ARGR + The SDMMC_ARGR register contains a 32-bit + command argument, which is sent to a card as part of a + command message. + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument. These bits can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). Command argument sent to a card as part of a + command message. If a command contains an argument, + it must be loaded into this register before writing a + command to the command register. + 0 + 32 + + + + + SDMMC_CMDR + SDMMC_CMDR + The SDMMC_CMDR register contains the command + index and command type bits. The command index is sent to + a card as part of a command message. The command type + bits control the command path state machine + (CPSM). + 0xC + 0x20 + read-write + 0x00000000 + + + CMDINDEX + Command index. This bit can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). The command index is sent to the card as part of + a command message. + 0 + 6 + + + CMDTRANS + The CPSM treats the command as a data + transfer command, stops the interrupt period, and + signals DataEnable to the DPSM This bit can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). If this bit is set, the CPSM issues an end of + interrupt period and issues DataEnable signal to the + DPSM when the command is sent. + 6 + 1 + + + CMDSTOP + The CPSM treats the command as a Stop + Transmission command and signals Abort to the DPSM. + This bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). If this bit is set, the CPSM + issues the Abort signal to the DPSM when the command + is sent. + 7 + 1 + + + WAITRESP + Wait for response bits. This bit can + only be written by firmware when CPSM is disabled + (CPSMEN = 0). They are used to configure whether the + CPSM is to wait for a response, and if yes, which + kind of response. + 8 + 2 + + + WAITINT + CPSM waits for interrupt request. If + this bit is set, the CPSM disables command timeout + and waits for an card interrupt request (Response). + If this bit is cleared in the CPSM Wait state, will + cause the abort of the interrupt mode. + 10 + 1 + + + WAITPEND + CPSM Waits for end of data transfer + (CmdPend internal signal) from DPSM. This bit when + set, the CPSM waits for the end of data transfer + trigger before it starts sending a command. WAITPEND + is only taken into account when DTMODE = MMC stream + data transfer, WIDBUS = 1-bit wide bus mode, DPSMACT + = 1 and DTDIR = from host to card. + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit This bit is written 1 by firmware, and cleared by + hardware when the CPSM enters the Idle state. If this + bit is set, the CPSM is enabled. When DTEN = 1, no + command will be transfered nor boot procedure will be + started. CPSMEN is cleared to 0. + 12 + 1 + + + DTHOLD + Hold new data block transmission and + reception in the DPSM. If this bit is set, the DPSM + will not move from the Wait_S state to the Send state + or from the Wait_R state to the Receive + state. + 13 + 1 + + + BOOTMODE + Select the boot mode procedure to be + used. This bit can only be written by firmware when + CPSM is disabled (CPSMEN = 0) + 14 + 1 + + + BOOTEN + Enable boot mode + procedure. + 15 + 1 + + + CMDSUSPEND + The CPSM treats the command as a Suspend + or Resume command and signals interrupt period + start/end. This bit can only be written by firmware + when CPSM is disabled (CPSMEN = 0). CMDSUSPEND = 1 + and CMDTRANS = 0 Suspend command, start interrupt + period when response bit BS=0. CMDSUSPEND = 1 and + CMDTRANS = 1 Resume command with data, end interrupt + period when response bit DF=1. + 16 + 1 + + + + + SDMMC_RESP1R + SDMMC_RESP1R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x10 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table404. + 0 + 32 + + + + + SDMMC_RESP2R + SDMMC_RESP2R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table404. + 0 + 32 + + + + + SDMMC_RESP3R + SDMMC_RESP3R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table404. + 0 + 32 + + + + + SDMMC_RESP4R + SDMMC_RESP4R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table404. + 0 + 32 + + + + + SDMMC_DTIMER + SDMMC_DTIMER + The SDMMC_DTIMER register contains the data + timeout period, in card bus clock periods. A counter + loads the value from the SDMMC_DTIMER register, and + starts decrementing when the data path state machine + (DPSM) enters the Wait_R or Busy state. If the timer + reaches 0 while the DPSM is in either of these states, + the timeout status flag is set. + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data and R1b busy timeout period This + bit can only be written when the CPSM and DPSM are + not active (CPSMACT = 0 and DPSMACT = 0). Data and + R1b busy timeout period expressed in card bus clock + periods. + 0 + 32 + + + + + SDMMC_DLENR + SDMMC_DLENR + The SDMMC_DLENR register contains the number + of data bytes to be transferred. The value is loaded into + the data counter when data transfer starts. + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value This register can only + be written by firmware when DPSM is inactive (DPSMACT + = 0). Number of data bytes to be transferred. When + DDR = 1 DATALENGTH is truncated to a multiple of 2. + (The last odd byte is not transfered) When DATALENGTH + = 0 no data will be transfered, when requested by a + CPSMEN and CMDTRANS = 1 also no command will be + transfered. DTEN and CPSMEN are cleared to + 0. + 0 + 25 + + + + + SDMMC_DCTRL + SDMMC_DCTRL + The SDMMC_DCTRL register control the data + path state machine (DPSM). + 0x2C + 0x20 + read-write + 0x00000000 + + + DTEN + Data transfer enable bit This bit can + only be written by firmware when DPSM is inactive + (DPSMACT = 0). This bit is cleared by Hardware when + data transfer completes. This bit shall only be used + to transfer data when no associated data transfer + command is used, i.e. shall not be used with SD or + eMMC cards. + 0 + 1 + + + DTDIR + Data transfer direction selection This + bit can only be written by firmware when DPSM is + inactive (DPSMACT = 0). + 1 + 1 + + + DTMODE + Data transfer mode selection. This bit + can only be written by firmware when DPSM is inactive + (DPSMACT = 0). + 2 + 2 + + + DBLOCKSIZE + Data block size This bit can only be + written by firmware when DPSM is inactive (DPSMACT = + 0). Define the data block length when the block data + transfer mode is selected: When DATALENGTH is not a + multiple of DBLOCKSIZE, the transfered data is + truncated at a multiple of DBLOCKSIZE. (Any remain + data will not be transfered.) When DDR = 1, + DBLOCKSIZE = 0000 shall not be used. (No data will be + transfered) + 4 + 4 + + + RWSTART + Read wait start. If this bit is set, + read wait operation starts. + 8 + 1 + + + RWSTOP + Read wait stop This bit is written by + firmware and auto cleared by hardware when the DPSM + moves from the READ_WAIT state to the WAIT_R or IDLE + state. + 9 + 1 + + + RWMOD + Read wait mode. This bit can only be + written by firmware when DPSM is inactive (DPSMACT = + 0). + 10 + 1 + + + SDIOEN + SD I/O interrupt enable functions This + bit can only be written by firmware when DPSM is + inactive (DPSMACT = 0). If this bit is set, the DPSM + enables the SD I/O card specific interrupt + operation. + 11 + 1 + + + BOOTACKEN + Enable the reception of the boot + acknowledgment. This bit can only be written by + firmware when DPSM is inactive (DPSMACT = + 0). + 12 + 1 + + + FIFORST + FIFO reset, will flush any remaining + data. This bit can only be written by firmware when + IDMAEN= 0 and DPSM is active (DPSMACT = 1). This bit + will only take effect when a transfer error or + transfer hold occurs. + 13 + 1 + + + + + SDMMC_DCNTR + SDMMC_DCNTR + The SDMMC_DCNTR register loads the value + from the data length register (see SDMMC_DLENR) when the + DPSM moves from the Idle state to the Wait_R or Wait_S + state. As data is transferred, the counter decrements the + value until it reaches 0. The DPSM then moves to the Idle + state and when there has been no error, the data status + end flag (DATAEND) is set. + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value When read, the number + of remaining data bytes to be transferred is + returned. Write has no effect. + 0 + 27 + + + + + SDMMC_STAR + SDMMC_STAR + The SDMMC_STAR register is a read-only + register. It contains two types of flag:Static flags + (bits [29,21,11:0]): these bits remain asserted until + they are cleared by writing to the SDMMC interrupt Clear + register (see SDMMC_ICR)Dynamic flags (bits [20:12]): + these bits change state depending on the state of the + underlying logic (for example, FIFO full and empty flags + are asserted and de-asserted as data while written to the + FIFO) + 0x34 + 0x20 + read-only + 0x00000000 + + + CCRCFAIL + Command response received (CRC check + failed). Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 0 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed). Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 1 + 1 + + + CTIMEOUT + Command response timeout. Interrupt flag + is cleared by writing corresponding interrupt clear + bit in SDMMC_ICR. The Command Timeout period has a + fixed value of 64 SDMMC_CK clock + periods. + 2 + 1 + + + DTIMEOUT + Data timeout. Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 3 + 1 + + + TXUNDERR + Transmit FIFO underrun error or IDMA + read transfer error. Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 4 + 1 + + + RXOVERR + Received FIFO overrun error or IDMA + write transfer error. Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 5 + 1 + + + CMDREND + Command response received (CRC check + passed, or no CRC). Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 6 + 1 + + + CMDSENT + Command sent (no response required). + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 7 + 1 + + + DATAEND + Data transfer ended correctly. (data + counter, DATACOUNT is zero and no errors occur). + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 8 + 1 + + + DHOLD + Data transfer Hold. Interrupt flag is + cleared by writing corresponding interrupt clear bit + in SDMMC_ICR. + 9 + 1 + + + DBCKEND + Data block sent/received. (CRC check + passed) and DPSM moves to the READWAIT state. + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 10 + 1 + + + DABORT + Data transfer aborted by CMD12. + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 11 + 1 + + + DPSMACT + Data path state machine active, i.e. not + in Idle state. This is a hardware status flag only, + does not generate an interrupt. + 12 + 1 + + + CPSMACT + Command path state machine active, i.e. + not in Idle state. This is a hardware status flag + only, does not generate an interrupt. + 13 + 1 + + + TXFIFOHE + Transmit FIFO half empty At least half + the number of words can be written into the FIFO. + This bit is cleared when the FIFO becomes half+1 + full. + 14 + 1 + + + RXFIFOHF + Receive FIFO half full There are at + least half the number of words in the FIFO. This bit + is cleared when the FIFO becomes half+1 + empty. + 15 + 1 + + + TXFIFOF + Transmit FIFO full This is a hardware + status flag only, does not generate an interrupt. + This bit is cleared when one FIFO location becomes + empty. + 16 + 1 + + + RXFIFOF + Receive FIFO full This bit is cleared + when one FIFO location becomes empty. + 17 + 1 + + + TXFIFOE + Transmit FIFO empty This bit is cleared + when one FIFO location becomes full. + 18 + 1 + + + RXFIFOE + Receive FIFO empty This is a hardware + status flag only, does not generate an interrupt. + This bit is cleared when one FIFO location becomes + full. + 19 + 1 + + + BUSYD0 + Inverted value of SDMMC_D0 line (Busy), + sampled at the end of a CMD response and a second + time 2 SDMMC_CK cycles after the CMD response. This + bit is reset to not busy when the SDMMCD0 line + changes from busy to not busy. This bit does not + signal busy due to data transfer. This is a hardware + status flag only, it does not generate an + interrupt. + 20 + 1 + + + BUSYD0END + end of SDMMC_D0 Busy following a CMD + response detected. This indicates only end of busy + following a CMD response. This bit does not signal + busy due to data transfer. Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 21 + 1 + + + SDIOIT + SDIO interrupt received. Interrupt flag + is cleared by writing corresponding interrupt clear + bit in SDMMC_ICR. + 22 + 1 + + + ACKFAIL + Boot acknowledgment received (boot + acknowledgment check fail). Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 23 + 1 + + + ACKTIMEOUT + Boot acknowledgment timeout. Interrupt + flag is cleared by writing corresponding interrupt + clear bit in SDMMC_ICR. + 24 + 1 + + + VSWEND + Voltage switch critical timing section + completion. Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 25 + 1 + + + CKSTOP + SDMMC_CK stopped in Voltage switch + procedure. Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 26 + 1 + + + IDMATE + IDMA transfer error. Interrupt flag is + cleared by writing corresponding interrupt clear bit + in SDMMC_ICR. + 27 + 1 + + + IDMABTC + IDMA buffer transfer complete. interrupt + flag is cleared by writing corresponding interrupt + clear bit in SDMMC_ICR. + 28 + 1 + + + + + SDMMC_ICR + SDMMC_ICR + The SDMMC_ICR register is a write-only + register. Writing a bit with 1 clears the corresponding + bit in the SDMMC_STAR status register. + 0x38 + 0x20 + read-write + 0x00000000 + + + CCRCFAILC + CCRCFAIL flag clear bit Set by software + to clear the CCRCFAIL flag. + 0 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit Set by software + to clear the DCRCFAIL flag. + 1 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit Set by software + to clear the CTIMEOUT flag. + 2 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit Set by software + to clear the DTIMEOUT flag. + 3 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit Set by software + to clear TXUNDERR flag. + 4 + 1 + + + RXOVERRC + RXOVERR flag clear bit Set by software + to clear the RXOVERR flag. + 5 + 1 + + + CMDRENDC + CMDREND flag clear bit Set by software + to clear the CMDREND flag. + 6 + 1 + + + CMDSENTC + CMDSENT flag clear bit Set by software + to clear the CMDSENT flag. + 7 + 1 + + + DATAENDC + DATAEND flag clear bit Set by software + to clear the DATAEND flag. + 8 + 1 + + + DHOLDC + DHOLD flag clear bit Set by software to + clear the DHOLD flag. + 9 + 1 + + + DBCKENDC + DBCKEND flag clear bit Set by software + to clear the DBCKEND flag. + 10 + 1 + + + DABORTC + DABORT flag clear bit Set by software to + clear the DABORT flag. + 11 + 1 + + + BUSYD0ENDC + BUSYD0END flag clear bit Set by software + to clear the BUSYD0END flag. + 21 + 1 + + + SDIOITC + SDIOIT flag clear bit Set by software to + clear the SDIOIT flag. + 22 + 1 + + + ACKFAILC + ACKFAIL flag clear bit Set by software + to clear the ACKFAIL flag. + 23 + 1 + + + ACKTIMEOUTC + ACKTIMEOUT flag clear bit Set by + software to clear the ACKTIMEOUT flag. + 24 + 1 + + + VSWENDC + VSWEND flag clear bit Set by software to + clear the VSWEND flag. + 25 + 1 + + + CKSTOPC + CKSTOP flag clear bit Set by software to + clear the CKSTOP flag. + 26 + 1 + + + IDMATEC + IDMA transfer error clear bit Set by + software to clear the IDMATE flag. + 27 + 1 + + + IDMABTCC + IDMA buffer transfer complete clear bit + Set by software to clear the IDMABTC + flag. + 28 + 1 + + + + + SDMMC_MASKR + SDMMC_MASKR + The interrupt mask register determines which + status flags generate an interrupt request by setting the + corresponding bit to 1. + 0x3C + 0x20 + read-write + 0x00000000 + + + CCRCFAILIE + Command CRC fail interrupt enable Set + and cleared by software to enable/disable interrupt + caused by command CRC failure. + 0 + 1 + + + DCRCFAILIE + Data CRC fail interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data CRC failure. + 1 + 1 + + + CTIMEOUTIE + Command timeout interrupt enable Set and + cleared by software to enable/disable interrupt + caused by command timeout. + 2 + 1 + + + DTIMEOUTIE + Data timeout interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data timeout. + 3 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt enable + Set and cleared by software to enable/disable + interrupt caused by Tx FIFO underrun + error. + 4 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt enable + Set and cleared by software to enable/disable + interrupt caused by Rx FIFO overrun + error. + 5 + 1 + + + CMDRENDIE + Command response received interrupt + enable Set and cleared by software to enable/disable + interrupt caused by receiving command + response. + 6 + 1 + + + CMDSENTIE + Command sent interrupt enable Set and + cleared by software to enable/disable interrupt + caused by sending command. + 7 + 1 + + + DATAENDIE + Data end interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data end. + 8 + 1 + + + DHOLDIE + Data hold interrupt enable Set and + cleared by software to enable/disable the interrupt + generated when sending new data is hold in the DPSM + Wait_S state. + 9 + 1 + + + DBCKENDIE + Data block end interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data block end. + 10 + 1 + + + DABORTIE + Data transfer aborted interrupt enable + Set and cleared by software to enable/disable + interrupt caused by a data transfer being + aborted. + 11 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt enable Set + and cleared by software to enable/disable interrupt + caused by Tx FIFO half empty. + 14 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt enable Set + and cleared by software to enable/disable interrupt + caused by Rx FIFO half full. + 15 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt enable Set and + cleared by software to enable/disable interrupt + caused by Rx FIFO full. + 17 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt enable Set and + cleared by software to enable/disable interrupt + caused by Tx FIFO empty. + 18 + 1 + + + BUSYD0ENDIE + BUSYD0END interrupt enable Set and + cleared by software to enable/disable the interrupt + generated when SDMMC_D0 signal changes from busy to + NOT busy following a CMD response. + 21 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable Set and cleared by software to enable/disable + the interrupt generated when receiving the SDIO mode + interrupt. + 22 + 1 + + + ACKFAILIE + Acknowledgment Fail interrupt enable Set + and cleared by software to enable/disable interrupt + caused by acknowledgment Fail. + 23 + 1 + + + ACKTIMEOUTIE + Acknowledgment timeout interrupt enable + Set and cleared by software to enable/disable + interrupt caused by acknowledgment + timeout. + 24 + 1 + + + VSWENDIE + Voltage switch critical timing section + completion interrupt enable Set and cleared by + software to enable/disable the interrupt generated + when voltage switch critical timing section + completion. + 25 + 1 + + + CKSTOPIE + Voltage Switch clock stopped interrupt + enable Set and cleared by software to enable/disable + interrupt caused by Voltage Switch clock + stopped. + 26 + 1 + + + IDMABTCIE + IDMA buffer transfer complete interrupt + enable Set and cleared by software to enable/disable + the interrupt generated when the IDMA has transferred + all data belonging to a memory buffer. + 28 + 1 + + + + + SDMMC_ACKTIMER + SDMMC_ACKTIMER + The SDMMC_ACKTIMER register contains the + acknowledgment timeout period, in SDMMC_CK bus clock + periods. A counter loads the value from the + SDMMC_ACKTIMER register, and starts decrementing when the + data path state machine (DPSM) enters the Wait_Ack state. + If the timer reaches 0 while the DPSM is in this states, + the acknowledgment timeout status flag is + set. + 0x40 + 0x20 + read-write + 0x00000000 + + + ACKTIME + Boot acknowledgment timeout period This + bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). Boot acknowledgment timeout + period expressed in card bus clock + periods. + 0 + 25 + + + + + SDMMC_IDMACTRLR + SDMMC_IDMACTRLR + The receive and transmit FIFOs can be read + or written as 32-bit wide registers. The FIFOs contain 32 + entries on 32 sequential addresses. This allows the CPU + to use its load and store multiple operands to read + from/write to the FIFO. + 0x50 + 0x20 + read-write + 0x00000000 + + + IDMAEN + IDMA enable This bit can only be written + by firmware when DPSM is inactive (DPSMACT = + 0). + 0 + 1 + + + IDMABMODE + Buffer mode selection. This bit can only + be written by firmware when DPSM is inactive (DPSMACT + = 0). + 1 + 1 + + + IDMABACT + Double buffer mode active buffer + indication This bit can only be written by firmware + when DPSM is inactive (DPSMACT = 0). When IDMA is + enabled this bit is toggled by + hardware. + 2 + 1 + + + + + SDMMC_IDMABSIZER + SDMMC_IDMABSIZER + The SDMMC_IDMABSIZER register contains the + buffers size when in double buffer + configuration. + 0x54 + 0x20 + read-write + 0x00000000 + + + IDMABNDT + Number of transfers per buffer. This + 8-bit value shall be multiplied by 8 to get the size + of the buffer in 32-bit words and by 32 to get the + size of the buffer in bytes. Example: IDMABNDT = + 0x01: buffer size = 8 words = 32 bytes. These bits + can only be written by firmware when DPSM is inactive + (DPSMACT = 0). + 5 + 8 + + + + + SDMMC_IDMABASE0R + SDMMC_IDMABASE0R + The SDMMC_IDMABASE0R register contains the + memory buffer base address in single buffer configuration + and the buffer 0 base address in double buffer + configuration. + 0x58 + 0x20 + read-write + 0x00000000 + + + IDMABASE0 + Buffer 0 memory base address bits + [31:2], shall be word aligned (bit [1:0] are always 0 + and read only). This register can be written by + firmware when DPSM is inactive (DPSMACT = 0), and can + dynamically be written by firmware when DPSM active + (DPSMACT = 1) and memory buffer 0 is inactive + (IDMABACT = 1). + 0 + 32 + + + + + SDMMC_IDMABASE1R + SDMMC_IDMABASE1R + The SDMMC_IDMABASE1R register contains the + double buffer configuration second buffer memory base + address. + 0x5C + 0x20 + read-write + 0x00000000 + + + IDMABASE1 + Buffer 1 memory base address, shall be + word aligned (bit [1:0] are always 0 and read only). + This register can be written by firmware when DPSM is + inactive (DPSMACT = 0), and can dynamically be + written by firmware when DPSM active (DPSMACT = 1) + and memory buffer 1 is inactive (IDMABACT = + 0). + 0 + 32 + + + + + SDMMC_RESPCMDR + SDMMC_RESPCMDR + The SDMMC_RESPCMDR register contains the + command index field of the last command response + received. If the command response transmission does not + contain the command index field (long or OCR response), + the RESPCMD field is unknown, although it must contain + 111111b (the value of the reserved field from the + response). + 0x60 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index Read-only bit + field. Contains the command index of the last command + response received. + 0 + 6 + + + + + SDMMC_FIFOR + SDMMC_FIFOR + The receive and transmit FIFOs can be only + read or written as word (32-bit) wide registers. The + FIFOs contain 16 entries on sequential addresses. This + allows the CPU to use its load and store multiple + operands to read from/write to the FIFO.When accessing + SDMMC_FIFOR with half word or byte access an AHB bus + fault is generated. + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFODATA + Receive and transmit FIFO data This + register can only be read or written by firmware when + the DPSM is active (DPSMACT=1). The FIFO data + occupies 16 entries of 32-bit words. + 0 + 32 + + + + + SDMMC_VER + SDMMC_VER + SDMMC IP version register + 0x3F4 + 0x20 + read-only + 0x00000010 + + + MINREV + IP minor revision number. + 0 + 4 + + + MAJREV + IP major revision number. + 4 + 4 + + + + + SDMMC_ID + SDMMC_ID + SDMMC IP identification + register + 0x3F8 + 0x20 + read-only + 0x00140022 + + + IP_ID + SDMMC IP identification. + 0 + 32 + + + + + + + HDMI_CEC + HDMI-CEC controller + HDMI_CEC + 0x40006C00 + + 0x0 + 0x400 + registers + + + + CEC_CR + CEC_CR + CEC control register + 0x0 + 0X20 + 0x00000000 + + + TXEOM + Tx End Of Message + 2 + 1 + read-only + + + TXSOM + Tx Start Of Message + 1 + 1 + read-only + + + CECEN + CEC Enable + 0 + 1 + read-write + + + + + CEC_CFGR + CEC_CFGR + CEC configuration register + 0x4 + 0X20 + read-write + 0x00000000 + + + LSTN + Listen mode + 31 + 1 + + + OAR + Own addresses + configuration + 16 + 15 + + + SFTOP + SFT Option Bit + 8 + 1 + + + BRDNOGEN + Avoid Error-Bit Generation in + Broadcast + 7 + 1 + + + LBPEGEN + Generate Error-Bit on Long Bit Period + Error + 6 + 1 + + + BREGEN + Generate Error-Bit on Bit Rising + Error + 5 + 1 + + + BRESTP + Rx-Stop on Bit Rising + Error + 4 + 1 + + + RXTOL + Rx-Tolerance + 3 + 1 + + + SFT + Signal Free Time + 0 + 3 + + + + + CEC_TXDR + CEC_TXDR + CEC Tx data register + 0x8 + 0X20 + write-only + 0x00000000 + + + TXD + Tx Data register + 0 + 8 + + + + + CEC_RXDR + CEC_RXDR + CEC Rx Data Register + 0xC + 0X20 + read-only + 0x00000000 + + + RXD + Rx Data register + 0 + 8 + + + + + CEC_ISR + CEC_ISR + CEC Interrupt and Status + Register + 0x10 + 0X20 + read-write + 0x00000000 + + + TXACKE + Tx-Missing Acknowledge + Error + 12 + 1 + + + TXERR + Tx-Error + 11 + 1 + + + TXUDR + Tx-Buffer Underrun + 10 + 1 + + + TXEND + End of Transmission + 9 + 1 + + + TXBR + Tx-Byte Request + 8 + 1 + + + ARBLST + Arbitration Lost + 7 + 1 + + + RXACKE + Rx-Missing Acknowledge + 6 + 1 + + + LBPE + Rx-Long Bit Period Error + 5 + 1 + + + SBPE + Rx-Short Bit Period Error + 4 + 1 + + + BRE + Rx-Bit Rising Error + 3 + 1 + + + RXOVR + Rx-Overrun + 2 + 1 + + + RXEND + End Of Reception + 1 + 1 + + + RXBR + Rx-Byte Received + 0 + 1 + + + + + CEC_IER + CEC_IER + CEC interrupt enable register + 0x14 + 0X20 + read-write + 0x00000000 + + + TXACKIE + Tx-Missing Acknowledge Error Interrupt + Enable + 12 + 1 + + + TXERRIE + Tx-Error Interrupt Enable + 11 + 1 + + + TXUDRIE + Tx-Underrun Interrupt + Enable + 10 + 1 + + + TXENDIE + Tx-End Of Message Interrupt + Enable + 9 + 1 + + + TXBRIE + Tx-Byte Request Interrupt + Enable + 8 + 1 + + + ARBLSTIE + Arbitration Lost Interrupt + Enable + 7 + 1 + + + RXACKIE + Rx-Missing Acknowledge Error Interrupt + Enable + 6 + 1 + + + LBPEIE + Long Bit Period Error Interrupt + Enable + 5 + 1 + + + SBPEIE + Short Bit Period Error Interrupt + Enable + 4 + 1 + + + BREIE + Bit Rising Error Interrupt + Enable + 3 + 1 + + + RXOVRIE + Rx-Buffer Overrun Interrupt + Enable + 2 + 1 + + + RXENDIE + End Of Reception Interrupt + Enable + 1 + 1 + + + RXBRIE + Rx-Byte Received Interrupt + Enable + 0 + 1 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + FPU + Floating point interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CTRL + CTRL + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + LOAD + LOAD + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + VAL + VAL + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + Instruction access violation + flag + 1 + 1 + + + MUNSTKERR + Memory manager fault on unstacking for a + return from exception + 3 + 1 + + + MSTKERR + Memory manager fault on stacking for + exception entry. + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + Memory Management Fault Address Register + (MMAR) valid flag + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + MMFAR + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + BFAR + Bus fault address + 0 + 32 + + + + + AFSR + AFSR + Auxiliary fault status + register + 0x3C + 0x20 + read-write + 0x00000000 + + + IMPDEF + Implementation defined + 0 + 32 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISMCYCINT + DISMCYCINT + 0 + 1 + + + DISDEFWBUF + DISDEFWBUF + 1 + 1 + + + DISFOLD + DISFOLD + 2 + 1 + + + DISFPCA + DISFPCA + 8 + 1 + + + DISOOFP + DISOOFP + 9 + 1 + + + + + + + diff --git a/dev/svd/STM32F7x2.svd b/dev/svd/STM32F7x2.svd new file mode 100644 index 00000000000..2aee3fd510f --- /dev/null +++ b/dev/svd/STM32F7x2.svd @@ -0,0 +1,61861 @@ + + + STM32F7x2 + 1.1 + STM32F7x2 + + + CM7 + r0p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_UP_TIM10 + TIM1 Update interrupt and TIM10 + 25 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + TIM1_CC + TIM1 Capture Compare interrupt + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + MMS2 + Master mode selection 2 + 20 + 4 + + + OIS6 + Output Idle state 6 (OC6 + output) + 18 + 1 + + + OIS5 + Output Idle state 5 (OC5 + output) + 16 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection - + bit[2:0] + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + B2IF + Break 2 interrupt flag + 8 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + B2G + Break 2 generation + 8 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + OC4M_3 + Output Compare 4 mode - bit + 3 + 24 + 1 + + + OC3M_3 + Output Compare 3 mode - bit + 3 + 16 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 1 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + CC6P + Capture/Compare 6 output + polarity + 21 + 1 + + + CC6E + Capture/Compare 6 output + enable + 20 + 1 + + + CC5P + Capture/Compare 5 output + polarity + 17 + 1 + + + CC5E + Capture/Compare 5 output + enable + 16 + 1 + + + CC4NP + Capture/Compare 4 complementary output + polarity + 15 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 32 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + BK2P + Break 2 polarity + 25 + 1 + + + BK2E + Break 2 enable + 24 + 1 + + + BK2F + Break 2 filter + 20 + 4 + + + BKF + Break filter + 16 + 4 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x0000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M3 + Output Compare 5 mode + 16 + 1 + + + OC6M3 + Output Compare 6 mode + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x0000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CCR6 + CCR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x0000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + + + TIM8 + 0x40010400 + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + ADC2 + Analog-to-digital converter + ADC + 0x40012100 + + 0x0 + 0x51 + registers + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC1 + 0x40012000 + + + ADC3 + 0x40012200 + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + Low counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0xD + registers + + + ADC + ADC1 global interrupt + 18 + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + RESET + RESET bit + 0 + 1 + + + POLYSIZE + Polynomial size + 3 + 2 + + + REV_IN + Reverse input data + 5 + 2 + + + REV_OUT + Reverse output data + 7 + 1 + + + + + INIT + INIT + Initial CRC value + 0x10 + 0x20 + read-write + 0x00000000 + + + CRC_INIT + Programmable initial CRC + value + 0 + 32 + + + + + POL + POL + CRC polynomial + 0x14 + 0x20 + read-write + 0x00000000 + + + POL + Programmable polynomial + 0 + 32 + + + + + + + CRYP + Cryptographic processor + CRYP + 0x50060000 + + 0x0 + 0x400 + registers + + + AES + AES global interrupt + 79 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + KEYSIZE + Key size selection + 18 + 1 + + + GCMPH + Used only for GCM, GMAC and CMAC + algorithms and has no effect when other + 13 + 2 + + + DMAOUTEN + Enable DMA management of data output + phase + 12 + 1 + + + DMAINEN + Enable DMA management of data input + phase + 11 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + CCFIE + CCF flag interrupt enable + 9 + 1 + + + ERRC + Error clear + 8 + 1 + + + CCFC + Computation complete flag + clear + 7 + 1 + + + CHMOD + AES chaining mode + 5 + 2 + + + MODE + AES operating mode + 3 + 2 + + + DATATYPE + Data type selection (for data in and + data out to/from the cryptographic + block) + 1 + 2 + + + EN + AES enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x00000000 + + + Busy + Busy flag + 3 + 1 + + + WRERR + Write error flag + 2 + 1 + + + RDERR + Read error flag + 1 + 1 + + + CCF + Computation complete flag + 0 + 1 + + + + + DINR + DINR + data input register + 0x8 + 0x20 + read-write + 0x00000000 + + + DINR + Data input + 0 + 32 + + + + + DOUTR + DOUTR + data output register + 0xC + 0x20 + read-only + 0x00000000 + + + DOUTR + Data output + 0 + 32 + + + + + KEYR0 + KEYR0 + key register + 0x10 + 0x20 + read-write + 0x00000000 + + + KEYR0 + Data output register + 0 + 31 + + + + + KEYR1 + KEYR1 + key register + 0x14 + 0x20 + read-write + 0x00000000 + + + KEYR1 + Data output register + 0 + 32 + + + + + KEYR2 + KEYR2 + key register + 0x18 + 0x20 + read-only + 0x00000000 + + + KEYR2 + Data output register + 0 + 31 + + + + + KEYR3 + KEYR3 + key register + 0x1C + 0x20 + read-only + 0x00000000 + + + KEYR3 + Data output register + 0 + 32 + + + + + IVR0 + IVR0 + initialization vector register + 0x20 + 0x20 + read-write + 0x00000000 + + + IVR0 + initialization vector + register + 0 + 32 + + + + + IVR1 + IVR1 + initialization vector register + 0x24 + 0x20 + read-write + 0x00000000 + + + IVR1 + Initialization vector + register + 0 + 32 + + + + + IVR2 + IVR2 + initialization vector register + 0x28 + 0x20 + read-write + 0x00000000 + + + IVR2 + Initialization vector + register + 0 + 32 + + + + + IVR3 + IVR3 + initialization vector register + 0x2C + 0x20 + read-write + 0x00000000 + + + IVR3 + Initialization vector + register + 0 + 32 + + + + + KEYR4 + KEYR4 + key registers + 0x30 + 0x20 + read-write + 0x00000000 + + + KEYR4 + Data output register + 0 + 32 + + + + + KEYR5 + KEYR5 + key registers + 0x34 + 0x20 + read-write + 0x00000000 + + + KEYR5 + Data output register + 0 + 32 + + + + + KEYR6 + KEYR6 + key registers + 0x38 + 0x20 + read-write + 0x00000000 + + + KEYR6 + Data output register + 0 + 32 + + + + + KEYR7 + KEYR7 + key registers + 0x3C + 0x20 + read-write + 0x00000000 + + + KEYR7 + Data output register + 0 + 32 + + + + + SUSP0R + SUSP0R + Suspend registers + 0x40 + 0x20 + read-write + 0x00000000 + + + SUSP0R + AES Suspend + 0 + 32 + + + + + SUSP1R + SUSP1R + Suspend registers + 0x44 + 0x20 + read-write + 0x00000000 + + + SUSP1R + AES Suspend + 0 + 32 + + + + + SUSP2R + SUSP2R + Suspend registers + 0x48 + 0x20 + read-write + 0x00000000 + + + SUSP2R + AES Suspend + 0 + 32 + + + + + SUSP3R + SUSP3R + Suspend registers + 0x4C + 0x20 + read-write + 0x00000000 + + + SUSP3R + IV127 + 0 + 32 + + + + + SUSP4R + SUSP4R + Suspend registers + 0x50 + 0x20 + read-write + 0x00000000 + + + SUSP4R + AES Suspend + 0 + 32 + + + + + SUSP5R + SUSP5R + Suspend registers + 0x54 + 0x20 + read-write + 0x00000000 + + + SUSP5R + AES Suspend + 0 + 32 + + + + + SUSP6R + SUSP6R + Suspend registers + 0x58 + 0x20 + read-write + 0x00000000 + + + SUSP6R + AES Suspend + 0 + 32 + + + + + SUSP7R + SUSP7R + Suspend registers + 0x5C + 0x20 + read-write + 0x00000000 + + + SUSP7R + AES Suspend + 0 + 32 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + FPU + FPU global interrupt + 81 + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + IM0 + Interrupt Mask on line 0 + 0 + 1 + + + IM1 + Interrupt Mask on line 1 + 1 + 1 + + + IM2 + Interrupt Mask on line 2 + 2 + 1 + + + IM3 + Interrupt Mask on line 3 + 3 + 1 + + + IM4 + Interrupt Mask on line 4 + 4 + 1 + + + IM5 + Interrupt Mask on line 5 + 5 + 1 + + + IM6 + Interrupt Mask on line 6 + 6 + 1 + + + IM7 + Interrupt Mask on line 7 + 7 + 1 + + + IM8 + Interrupt Mask on line 8 + 8 + 1 + + + MI9 + Interrupt Mask on line 9 + 9 + 1 + + + IM10 + Interrupt Mask on line 10 + 10 + 1 + + + IM11 + Interrupt Mask on line 11 + 11 + 1 + + + IM12 + Interrupt Mask on line 12 + 12 + 1 + + + IM13 + Interrupt Mask on line 13 + 13 + 1 + + + IM14 + Interrupt Mask on line 14 + 14 + 1 + + + IM15 + Interrupt Mask on line 15 + 15 + 1 + + + IM16 + Interrupt Mask on line 16 + 16 + 1 + + + IM17 + Interrupt Mask on line 17 + 17 + 1 + + + IM18 + Interrupt Mask on line 18 + 18 + 1 + + + IM19 + Interrupt Mask on line 19 + 19 + 1 + + + IM20 + Interrupt Mask on line 20 + 20 + 1 + + + IM21 + Interrupt Mask on line 21 + 21 + 1 + + + IM22 + Interrupt Mask on line 22 + 22 + 1 + + + IM23 + Interrupt Mask on line 23 + 23 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + EM0 + Event Mask on line 0 + 0 + 1 + + + EM1 + Event Mask on line 1 + 1 + 1 + + + EM2 + Event Mask on line 2 + 2 + 1 + + + EM3 + Event Mask on line 3 + 3 + 1 + + + EM4 + Event Mask on line 4 + 4 + 1 + + + EM5 + Event Mask on line 5 + 5 + 1 + + + EM6 + Event Mask on line 6 + 6 + 1 + + + EM7 + Event Mask on line 7 + 7 + 1 + + + EM8 + Event Mask on line 8 + 8 + 1 + + + EM9 + Event Mask on line 9 + 9 + 1 + + + EM10 + Event Mask on line 10 + 10 + 1 + + + EM11 + Event Mask on line 11 + 11 + 1 + + + EM12 + Event Mask on line 12 + 12 + 1 + + + EM13 + Event Mask on line 13 + 13 + 1 + + + EM14 + Event Mask on line 14 + 14 + 1 + + + EM15 + Event Mask on line 15 + 15 + 1 + + + EM16 + Event Mask on line 16 + 16 + 1 + + + EM17 + Event Mask on line 17 + 17 + 1 + + + EM18 + Event Mask on line 18 + 18 + 1 + + + EM19 + Event Mask on line 19 + 19 + 1 + + + EM20 + Event Mask on line 20 + 20 + 1 + + + EM21 + Event Mask on line 21 + 21 + 1 + + + EM22 + Event Mask on line 22 + 22 + 1 + + + EM23 + Event Mask on line 23 + 23 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + TR23 + Rising trigger event configuration of + line 23 + 23 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + TR23 + Falling trigger event configuration of + line 23 + 23 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + SWIER23 + Software Interrupt on line + 22 + 23 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + PR23 + Pending bit 23 + 23 + 1 + + + + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + read-write + 0x00000000 + + + LATENCY + Latency + 0 + 3 + + + PRFTEN + Prefetch enable + 8 + 1 + + + ARTEN + ART Accelerator Enable + 9 + 1 + + + ARTRST + ART Accelerator reset + 11 + 1 + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEYR + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + ERSERR + Erase Sequence Error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase of sectors 0 to + 11 + 2 + 1 + + + SNB + Sector number + 3 + 5 + + + PSIZE + Program size + 8 + 2 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + RDERRIE + PCROP error interrupt + enable + 26 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x0FFFAAED + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + IWDG_SW + WDG_SW User option bytes + 5 + 1 + + + nRST_STOP + nRST_STOP User option + bytes + 6 + 1 + + + nRST_STDBY + nRST_STDBY User option + bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 12 + + + WWDG_SW + User option bytes + 4 + 1 + + + IWDG_STOP + Independent watchdog counter freeze in + Stop mode + 31 + 1 + + + IWDG_STDBY + Independent watchdog counter freeze in + standby mode + 30 + 1 + + + + + OPTCR1 + OPTCR1 + Flash option control register + 1 + 0x18 + 0x20 + read-write + 0x0FFF0000 + + + BOOT_ADD1 + Boot base address when Boot pin + =1 + 16 + 16 + + + BOOT_ADD0 + Boot base address when Boot pin + =0 + 0 + 16 + + + + + OPTCR2 + OPTCR2 + Flash option control register + 0x1C + 0x20 + read-write + 0x800000FF + + + PCROP_RDP + PCROP zone preserved when RDP level + decreased + 31 + 1 + + + PCROP + PCROP option byte + 0 + 8 + + + + + + + FMC + Flexible memory controller + FSMC + 0xA0000000 + + 0x0 + 0x1000 + registers + + + FSMC + FMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + WFDIS + Write FIFO Disable + 21 + 1 + + + CPSIZE + CRAM page size + 16 + 3 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + CPSIZE + CRAM page size + 16 + 3 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + CPSIZE + CRAM page size. + 16 + 3 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + CPSIZE + CRAM page size. + 16 + 3 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR + PCR + PC Card/NAND Flash control + register + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR + SR + FIFO status and interrupt + register + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM + PMEM + Common memory space timing + register + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT + PATT + Attribute memory space timing + register + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR + ECCR + ECC result register + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + BUSTURN + Bus turnaround phase + duration + 16 + 4 + + + + + SDCR1 + SDCR1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDCR2 + SDCR2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + + + SDTR1 + SDTR1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDTR2 + SDTR2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDCMR + SDCMR + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + MODE + Command mode + 0 + 3 + write-only + + + CTB2 + Command target bank 2 + 3 + 1 + write-only + + + CTB1 + Command target bank 1 + 4 + 1 + write-only + + + NRFS + Number of Auto-refresh + 5 + 4 + read-write + + + MRD + Mode Register definition + 9 + 13 + read-write + + + + + SDRTR + SDRTR + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag + 0 + 1 + write-only + + + COUNT + Refresh Timer Count + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + MODES1 + Status Mode for Bank 1 + 1 + 2 + + + MODES2 + Status Mode for Bank 2 + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + OC4M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC3M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + TIM2 option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + ITR1_RMP + Internal trigger 1 remap + 10 + 2 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + OC4M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC3M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM4 + 0x40000800 + + TIM4 + TIM4 global interrupt + 30 + + + + TIM5 + General purpose timers + TIM + 0x40000C00 + + 0x0 + 0x400 + registers + + + TIM5 + TIM5 global interrupt + 50 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + OC4M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC3M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR + OR + option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + TI4_RMP + Timer Input 4 remap + 6 + 2 + + + + + + + GPIOH + General-purpose I/Os + GPIO + 0x40021C00 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function + lowregister + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOF + 0x40021400 + + + GPIOG + 0x40021800 + + + GPIOI + 0x40022000 + + + GPIOE + 0x40021000 + + + GPIOD + 0x40020C00 + + + GPIOC + 0x40020800 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + + + TIM13 + General-purpose-timers + TIM + 0x40001C00 + + 0x0 + 0x400 + registers + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-only + 0x00000000 + + + Res + Res. + 0 + 32 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + TI1_RMP + TIM11 Input 1 remapping + capability + 0 + 2 + + + + + + + TIM14 + 0x40002000 + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + + TIM10 + 0x40014400 + + + TIM11 + 0x40014800 + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + WVU + Watchdog counter window value + update + 2 + 1 + + + + + WINR + WINR + Window register + 0x10 + 0x20 + read-write + 0x00000000 + + + WIN + Watchdog counter window + value + 0 + 12 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + PE + Peripheral enable + 0 + 1 + + + TXIE + TX Interrupt enable + 1 + 1 + + + RXIE + RX Interrupt enable + 2 + 1 + + + ADDRIE + Address match interrupt enable (slave + only) + 3 + 1 + + + NACKIE + Not acknowledge received interrupt + enable + 4 + 1 + + + STOPIE + STOP detection Interrupt + enable + 5 + 1 + + + TCIE + Transfer Complete interrupt + enable + 6 + 1 + + + ERRIE + Error interrupts enable + 7 + 1 + + + DNF + Digital noise filter + 8 + 4 + + + ANFOFF + Analog noise filter OFF + 12 + 1 + + + TXDMAEN + DMA transmission requests + enable + 14 + 1 + + + RXDMAEN + DMA reception requests + enable + 15 + 1 + + + SBC + Slave byte control + 16 + 1 + + + NOSTRETCH + Clock stretching disable + 17 + 1 + + + GCEN + General call enable + 19 + 1 + + + SMBHEN + SMBus Host address enable + 20 + 1 + + + SMBDEN + SMBus Device Default address + enable + 21 + 1 + + + ALERTEN + SMBUS alert enable + 22 + 1 + + + PECEN + PEC enable + 23 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECBYTE + Packet error checking byte + 26 + 1 + + + AUTOEND + Automatic end mode (master + mode) + 25 + 1 + + + RELOAD + NBYTES reload mode + 24 + 1 + + + NBYTES + Number of bytes + 16 + 8 + + + NACK + NACK generation (slave + mode) + 15 + 1 + + + STOP + Stop generation (master + mode) + 14 + 1 + + + START + Start generation + 13 + 1 + + + HEAD10R + 10-bit address header only read + direction (master receiver mode) + 12 + 1 + + + ADD10 + 10-bit addressing mode (master + mode) + 11 + 1 + + + RD_WRN + Transfer direction (master + mode) + 10 + 1 + + + SADD + Slave address bit (master + mode) + 0 + 10 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + OA1 + Interface address + 0 + 10 + + + OA1MODE + Own Address 1 10-bit mode + 10 + 1 + + + OA1EN + Own Address 1 enable + 15 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + OA2 + Interface address + 1 + 7 + + + OA2MSK + Own Address 2 masks + 8 + 3 + + + OA2EN + Own Address 2 enable + 15 + 1 + + + + + TIMINGR + TIMINGR + Timing register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low period (master + mode) + 0 + 8 + + + SCLH + SCL high period (master + mode) + 8 + 8 + + + SDADEL + Data hold time + 16 + 4 + + + SCLDEL + Data setup time + 20 + 4 + + + PRESC + Timing prescaler + 28 + 4 + + + + + TIMEOUTR + TIMEOUTR + Status register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + TIMEOUTA + Bus timeout A + 0 + 12 + + + TIDLE + Idle clock timeout + detection + 12 + 1 + + + TIMOUTEN + Clock timeout enable + 15 + 1 + + + TIMEOUTB + Bus timeout B + 16 + 12 + + + TEXTEN + Extended clock timeout + enable + 31 + 1 + + + + + ISR + ISR + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDCODE + Address match code (Slave + mode) + 17 + 7 + read-only + + + DIR + Transfer direction (Slave + mode) + 16 + 1 + read-only + + + BUSY + Bus busy + 15 + 1 + read-only + + + ALERT + SMBus alert + 13 + 1 + read-only + + + TIMEOUT + Timeout or t_low detection + flag + 12 + 1 + read-only + + + PECERR + PEC Error in reception + 11 + 1 + read-only + + + OVR + Overrun/Underrun (slave + mode) + 10 + 1 + read-only + + + ARLO + Arbitration lost + 9 + 1 + read-only + + + BERR + Bus error + 8 + 1 + read-only + + + TCR + Transfer Complete Reload + 7 + 1 + read-only + + + TC + Transfer Complete (master + mode) + 6 + 1 + read-only + + + STOPF + Stop detection flag + 5 + 1 + read-only + + + NACKF + Not acknowledge received + flag + 4 + 1 + read-only + + + ADDR + Address matched (slave + mode) + 3 + 1 + read-only + + + RXNE + Receive data register not empty + (receivers) + 2 + 1 + read-only + + + TXIS + Transmit interrupt status + (transmitters) + 1 + 1 + read-write + + + TXE + Transmit data register empty + (transmitters) + 0 + 1 + read-write + + + + + ICR + ICR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTCF + Alert flag clear + 13 + 1 + + + TIMOUTCF + Timeout detection flag + clear + 12 + 1 + + + PECCF + PEC Error flag clear + 11 + 1 + + + OVRCF + Overrun/Underrun flag + clear + 10 + 1 + + + ARLOCF + Arbitration lost flag + clear + 9 + 1 + + + BERRCF + Bus error flag clear + 8 + 1 + + + STOPCF + Stop detection flag clear + 5 + 1 + + + NACKCF + Not Acknowledge flag clear + 4 + 1 + + + ADDRCF + Address Matched flag clear + 3 + 1 + + + + + PECR + PECR + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PEC + Packet error checking + register + 0 + 8 + + + + + RXDR + RXDR + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + RXDATA + 8-bit receive data + 0 + 8 + + + + + TXDR + TXDR + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + TXDATA + 8-bit transmit data + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2C3 + 0x40005C00 + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + LPTIM1 + Low power timer + LPTIM + 0x40002400 + + 0x0 + 0x400 + registers + + + LP_Timer1 + LP Timer1 global interrupt + 93 + + + + ISR + ISR + Interrupt and Status Register + 0x0 + 0x20 + read-only + 0x00000000 + + + DOWN + Counter direction change up to + down + 6 + 1 + + + UP + Counter direction change down to + up + 5 + 1 + + + ARROK + Autoreload register update + OK + 4 + 1 + + + CMPOK + Compare register update OK + 3 + 1 + + + EXTTRIG + External trigger edge + event + 2 + 1 + + + ARRM + Autoreload match + 1 + 1 + + + CMPM + Compare match + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x4 + 0x20 + write-only + 0x00000000 + + + DOWNCF + Direction change to down Clear + Flag + 6 + 1 + + + UPCF + Direction change to UP Clear + Flag + 5 + 1 + + + ARROKCF + Autoreload register update OK Clear + Flag + 4 + 1 + + + CMPOKCF + Compare register update OK Clear + Flag + 3 + 1 + + + EXTTRIGCF + External trigger valid edge Clear + Flag + 2 + 1 + + + ARRMCF + Autoreload match Clear + Flag + 1 + 1 + + + CMPMCF + compare match Clear Flag + 0 + 1 + + + + + IER + IER + Interrupt Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + DOWNIE + Direction change to down Interrupt + Enable + 6 + 1 + + + UPIE + Direction change to UP Interrupt + Enable + 5 + 1 + + + ARROKIE + Autoreload register update OK Interrupt + Enable + 4 + 1 + + + CMPOKIE + Compare register update OK Interrupt + Enable + 3 + 1 + + + EXTTRIGIE + External trigger valid edge Interrupt + Enable + 2 + 1 + + + ARRMIE + Autoreload match Interrupt + Enable + 1 + 1 + + + CMPMIE + Compare match Interrupt + Enable + 0 + 1 + + + + + CFGR + CFGR + Configuration Register + 0xC + 0x20 + read-write + 0x00000000 + + + ENC + Encoder mode enable + 24 + 1 + + + COUNTMODE + counter mode enabled + 23 + 1 + + + PRELOAD + Registers update mode + 22 + 1 + + + WAVPOL + Waveform shape polarity + 21 + 1 + + + WAVE + Waveform shape + 20 + 1 + + + TIMOUT + Timeout enable + 19 + 1 + + + TRIGEN + Trigger enable and + polarity + 17 + 2 + + + TRIGSEL + Trigger selector + 13 + 3 + + + PRESC + Clock prescaler + 9 + 3 + + + TRGFLT + Configurable digital filter for + trigger + 6 + 2 + + + CKFLT + Configurable digital filter for external + clock + 3 + 2 + + + CKPOL + Clock Polarity + 1 + 2 + + + CKSEL + Clock selector + 0 + 1 + + + + + CR + CR + Control Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTSTRT + Timer start in continuous + mode + 2 + 1 + + + SNGSTRT + LPTIM start in single mode + 1 + 1 + + + ENABLE + LPTIM Enable + 0 + 1 + + + + + CMP + CMP + Compare Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CMP + Compare value + 0 + 16 + + + + + ARR + ARR + Autoreload Register + 0x18 + 0x20 + read-write + 0x00000001 + + + ARR + Auto reload value + 0 + 16 + + + + + CNT + CNT + Counter Register + 0x1C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 16 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + PVD + PVD through EXTI line detection + interrupt + 1 + + + + CR1 + CR1 + power control register + 0x0 + 0x20 + read-write + 0x0000C000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + LPUDS + Low-power regulator in deepsleep + under-drive mode + 10 + 1 + + + MRUDS + Main regulator in deepsleep under-drive + mode + 11 + 1 + + + ADCDC1 + ADCDC1 + 13 + 1 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ODEN + Over-drive enable + 16 + 1 + + + ODSWEN + Over-drive switching + enabled + 17 + 1 + + + UDEN + Under-drive enable in stop + mode + 18 + 2 + + + + + CSR1 + CSR1 + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUIF + Wakeup internal flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + ODRDY + Over-drive mode ready + 16 + 1 + read-write + + + ODSWRDY + Over-drive mode switching + ready + 17 + 1 + read-write + + + UDRDY + Under-drive ready flag + 18 + 2 + read-write + + + EIWUP + Enable internal wakeup + 8 + 1 + read-write + + + + + CR2 + CR2 + power control register + 0x8 + 0x20 + 0x00000000 + + + CWUPF1 + Clear Wakeup Pin flag for + PA0 + 0 + 1 + read-only + + + CWUPF2 + Clear Wakeup Pin flag for + PA2 + 1 + 1 + read-only + + + CWUPF3 + Clear Wakeup Pin flag for + PC1 + 2 + 1 + read-only + + + CWUPF4 + Clear Wakeup Pin flag for + PC13 + 3 + 1 + read-only + + + CWUPF5 + Clear Wakeup Pin flag for + PI8 + 4 + 1 + read-only + + + CWUPF6 + Clear Wakeup Pin flag for + PI11 + 5 + 1 + read-only + + + WUPP1 + Wakeup pin polarity bit for + PA0 + 8 + 1 + read-write + + + WUPP2 + Wakeup pin polarity bit for + PA2 + 9 + 1 + read-write + + + WUPP3 + Wakeup pin polarity bit for + PC1 + 10 + 1 + read-write + + + WUPP4 + Wakeup pin polarity bit for + PC13 + 11 + 1 + read-write + + + WUPP5 + Wakeup pin polarity bit for + PI8 + 12 + 1 + read-write + + + WUPP6 + Wakeup pin polarity bit for + PI11 + 13 + 1 + read-write + + + + + CSR2 + CSR2 + power control/status register + 0xC + 0x20 + 0x00000000 + + + WUPF1 + Wakeup Pin flag for PA0 + 0 + 1 + read-only + + + WUPF2 + Wakeup Pin flag for PA2 + 1 + 1 + read-only + + + WUPF3 + Wakeup Pin flag for PC1 + 2 + 1 + read-only + + + WUPF4 + Wakeup Pin flag for PC13 + 3 + 1 + read-only + + + WUPF5 + Wakeup Pin flag for PI8 + 4 + 1 + read-only + + + WUPF6 + Wakeup Pin flag for PI11 + 5 + 1 + read-only + + + EWUP1 + Enable Wakeup pin for PA0 + 8 + 1 + read-write + + + EWUP2 + Enable Wakeup pin for PA2 + 9 + 1 + read-write + + + EWUP3 + Enable Wakeup pin for PC1 + 10 + 1 + read-write + + + EWUP4 + Enable Wakeup pin for PC13 + 11 + 1 + read-write + + + EWUP5 + Enable Wakeup pin for PI8 + 12 + 1 + read-write + + + EWUP6 + Enable Wakeup pin for PI11 + 13 + 1 + read-write + + + + + + + QUADSPI + QuadSPI interface + QUADSPI + 0xA0001000 + + 0x0 + 0x1000 + registers + + + QuadSPI + QuadSPI global interrupt + 92 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PRESCALER + Clock prescaler + 24 + 8 + + + PMM + Polling match mode + 23 + 1 + + + APMS + Automatic poll mode stop + 22 + 1 + + + TOIE + TimeOut interrupt enable + 20 + 1 + + + SMIE + Status match interrupt + enable + 19 + 1 + + + FTIE + FIFO threshold interrupt + enable + 18 + 1 + + + TCIE + Transfer complete interrupt + enable + 17 + 1 + + + TEIE + Transfer error interrupt + enable + 16 + 1 + + + FTHRES + IFO threshold level + 8 + 5 + + + FSEL + FLASH memory selection + 7 + 1 + + + DFM + Dual-flash mode + 6 + 1 + + + SSHIFT + Sample shift + 4 + 1 + + + TCEN + Timeout counter enable + 3 + 1 + + + DMAEN + DMA enable + 2 + 1 + + + ABORT + Abort request + 1 + 1 + + + EN + Enable + 0 + 1 + + + + + DCR + DCR + device configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + FSIZE + FLASH memory size + 16 + 5 + + + CSHT + Chip select high time + 8 + 3 + + + CKMODE + Mode 0 / mode 3 + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + read-only + 0x00000000 + + + FLEVEL + FIFO level + 8 + 7 + + + BUSY + Busy + 5 + 1 + + + TOF + Timeout flag + 4 + 1 + + + SMF + Status match flag + 3 + 1 + + + FTF + FIFO threshold flag + 2 + 1 + + + TCF + Transfer complete flag + 1 + 1 + + + TEF + Transfer error flag + 0 + 1 + + + + + FCR + FCR + flag clear register + 0xC + 0x20 + read-write + 0x00000000 + + + CTOF + Clear timeout flag + 4 + 1 + + + CSMF + Clear status match flag + 3 + 1 + + + CTCF + Clear transfer complete + flag + 1 + 1 + + + CTEF + Clear transfer error flag + 0 + 1 + + + + + DLR + DLR + data length register + 0x10 + 0x20 + read-write + 0x00000000 + + + DL + Data length + 0 + 32 + + + + + CCR + CCR + communication configuration + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DDRM + Double data rate mode + 31 + 1 + + + DHHC + DDR hold half cycle + 30 + 1 + + + SIOO + Send instruction only once + mode + 28 + 1 + + + FMODE + Functional mode + 26 + 2 + + + DMODE + Data mode + 24 + 2 + + + DCYC + Number of dummy cycles + 18 + 5 + + + ABSIZE + Alternate bytes size + 16 + 2 + + + ABMODE + Alternate bytes mode + 14 + 2 + + + ADSIZE + Address size + 12 + 2 + + + ADMODE + Address mode + 10 + 2 + + + IMODE + Instruction mode + 8 + 2 + + + INSTRUCTION + Instruction + 0 + 8 + + + + + AR + AR + address register + 0x18 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Address + 0 + 32 + + + + + ABR + ABR + ABR + 0x1C + 0x20 + read-write + 0x00000000 + + + ALTERNATE + ALTERNATE + 0 + 32 + + + + + DR + DR + data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + PSMKR + PSMKR + polling status mask register + 0x24 + 0x20 + read-write + 0x00000000 + + + MASK + Status mask + 0 + 32 + + + + + PSMAR + PSMAR + polling status match register + 0x28 + 0x20 + read-write + 0x00000000 + + + MATCH + Status match + 0 + 32 + + + + + PIR + PIR + polling interval register + 0x2C + 0x20 + read-write + 0x00000000 + + + INTERVAL + Polling interval + 0 + 16 + + + + + LPTR + LPTR + low-power timeout register + 0x30 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Timeout period + 0 + 16 + + + + + + + RNG + Random number generator + RNG + 0x50060800 + + 0x0 + 0x400 + registers + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + RNG + Rng global interrupt + 80 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + IE + Interrupt enable + 3 + 1 + + + RNGEN + Random number generator + enable + 2 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + 0x00000000 + + + SEIS + Seed error interrupt + status + 6 + 1 + read-write + + + CEIS + Clock error interrupt + status + 5 + 1 + read-write + + + SECS + Seed error current status + 2 + 1 + read-only + + + CECS + Clock error current status + 1 + 1 + read-only + + + DRDY + Data ready + 0 + 1 + read-only + + + + + DR + DR + data register + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data + 0 + 32 + + + + + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Tamper or TimeStamp /CSS on LSE through + EXTI line 19 interrupts + 3 + + + RTC_ALARM + RTC alarms through EXTI line 18 + interrupts + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + BYPSHAD + Bypass the shadow + registers + 5 + 1 + + + FMT + Hour format + 6 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + BKP + Backup + 18 + 1 + + + COSEL + Calibration output + selection + 19 + 1 + + + POL + Output polarity + 20 + 1 + + + OSEL + Output selection + 21 + 2 + + + COE + Calibration output enable + 23 + 1 + + + ITSE + timestamp on internal event + enable + 24 + 1 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + RTC_TAMP2 detection flag + 14 + 1 + read-write + + + TAMP3F + RTC_TAMP3 detection flag + 15 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + ITSF + Internal tTime-stamp flag + 17 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAMPCR + TAMPCR + tamper configuration register + 0x40 + 0x20 + read-write + 0x00000000 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP3E + Tamper 3 detection enable + 5 + 1 + + + TAMP3TRG + Active level for tamper 3 + 6 + 1 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMP1IE + Tamper 1 interrupt enable + 16 + 1 + + + TAMP1NOERASE + Tamper 1 no erase + 17 + 1 + + + TAMP1MF + Tamper 1 mask flag + 18 + 1 + + + TAMP2IE + Tamper 2 interrupt enable + 19 + 1 + + + TAMP2NOERASE + Tamper 2 no erase + 20 + 1 + + + TAMP2MF + Tamper 2 mask flag + 21 + 1 + + + TAMP3IE + Tamper 3 interrupt enable + 22 + 1 + + + TAMP3NOERASE + Tamper 3 no erase + 23 + 1 + + + TAMP3MF + Tamper 3 mask flag + 24 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + OR + OR + option register + 0x4C + 0x20 + read-write + 0x00000000 + + + RTC_ALARM_TYPE + RTC_ALARM on PC13 output + type + 3 + 1 + + + TSINSEL + TIMESTAMP mapping + 1 + 1 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP20R + BKP20R + backup register + 0xA0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP21R + BKP21R + backup register + 0xA4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP22R + BKP22R + backup register + 0xA8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP23R + BKP23R + backup register + 0xAC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP24R + BKP24R + backup register + 0xB0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP25R + BKP25R + backup register + 0xB4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP26R + BKP26R + backup register + 0xB8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP27R + BKP27R + backup register + 0xBC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP28R + BKP28R + backup register + 0xC0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP29R + BKP29R + backup register + 0xC4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP30R + BKP30R + backup register + 0xC8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP31R + BKP31R + backup register + 0xCC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + PLLSAIRDY + PLLSAI clock ready flag + 29 + 1 + read-write + + + PLLSAION + PLLSAI enable + 28 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLSAIRDYC + PLLSAI Ready Interrupt + Clear + 22 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLSAIRDYIE + PLLSAI Ready Interrupt + Enable + 14 + 1 + read-write + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLSAIRDYF + PLLSAI ready interrupt + flag + 6 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOIRST + IO port I reset + 8 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + RNGRST + Random number generator module + reset + 6 + 1 + + + AESRST + AES module reset + 4 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FMCRST + Flexible memory controller module + reset + 0 + 1 + + + QSPIRST + Quad SPI memory controller + reset + 1 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM2 reset + 0 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + CECRST + HDMI-CEC reset + 27 + 1 + + + LPTIM1RST + Low power timer 1 reset + 9 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 reset + 0 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM11RST + TIM11 reset + 18 + 1 + + + SPI5RST + SPI5 reset + 20 + 1 + + + SAI1RST + SAI1 reset + 22 + 1 + + + SAI2RST + SAI2 reset + 23 + 1 + + + SDMMC1RST + SDMMC1 reset + 11 + 1 + + + SDMMC2RST + SDMMC2 reset + 7 + 1 + + + USBPHYCRST + USB OTG HS PHY controller + reset + 31 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + DTCMRAMEN + CCM data RAM clock enable + 20 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOIEN + IO port I clock enable + 8 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + RNGEN + Random number generator clock + enable + 6 + 1 + + + AESEN + AES module clock enable + 4 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FMCEN + Flexible memory controller module clock + enable + 0 + 1 + + + QSPIEN + Quad SPI memory controller clock + enable + 1 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + UART7EN + UART7 clock enable + 30 + 1 + + + UART8EN + UART8 clock enable + 31 + 1 + + + LPTIM1EN + Low power timer 1 clock + enable + 9 + 1 + + + RTCAPBEN + RTCAPB clock enable + 10 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4EN + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + SPI5EN + SPI5 clock enable + 20 + 1 + + + SAI1EN + SAI1 clock enable + 22 + 1 + + + SAI2EN + SAI2 clock enable + 23 + 1 + + + SDMMC1EN + SDMMC1 clock enable + 11 + 1 + + + SDMMC2EN + SDMMC2 clock enable + 7 + 1 + + + USBPHYCEN + USB OTG HS PHY controller clock + enable + 31 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOILPEN + IO port I clock enable during Sleep + mode + 8 + 1 + + + GPIOJLPEN + IO port J clock enable during Sleep + mode + 9 + 1 + + + GPIOKLPEN + IO port K clock enable during Sleep + mode + 10 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + SRAM3LPEN + SRAM 3 interface clock enable during + Sleep mode + 19 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + DMA2DLPEN + DMA2D clock enable during Sleep + mode + 23 + 1 + + + ETHMACLPEN + Ethernet MAC clock enable during Sleep + mode + 25 + 1 + + + ETHMACTXLPEN + Ethernet transmission clock enable + during Sleep mode + 26 + 1 + + + ETHMACRXLPEN + Ethernet reception clock enable during + Sleep mode + 27 + 1 + + + ETHMACPTPLPEN + Ethernet PTP clock enable during Sleep + mode + 28 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + AXILPEN + AXI to AHB bridge clock enable during + Sleep mode + 13 + 1 + + + DTCMLPEN + DTCM RAM interface clock enable during + Sleep mode + 20 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + RNGLPEN + Random number generator clock enable + during Sleep mode + 6 + 1 + + + AESLPEN + AES module clock enable during Sleep + mode + 4 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FMCLPEN + Flexible memory controller module clock + enable during Sleep mode + 0 + 1 + + + QSPILPEN + Quand SPI memory controller clock enable + during Sleep mode + 1 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during Sleep + mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during Sleep + mode + 31 + 1 + + + LPTIM1LPEN + low power timer 1 clock enable during + Sleep mode + 9 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI 4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + SPI5LPEN + SPI 5 clock enable during Sleep + mode + 20 + 1 + + + SAI1LPEN + SAI1 clock enable during sleep + mode + 22 + 1 + + + SAI2LPEN + SAI2 clock enable during sleep + mode + 23 + 1 + + + SDMMC1LPEN + SDMMC1 clock enable during Sleep + mode + 11 + 1 + + + SDMMC2LPEN + SDMMC2 clock enable during Sleep + mode + 7 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SR + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SQ + PLLI2S division factor for SAI1 + clock + 24 + 4 + + + PLLI2SN + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + PLLSAICFGR + PLLSAICFGR + PLL configuration register + 0x88 + 0x20 + read-write + 0x20003000 + + + PLLSAIN + PLLSAI division factor for + VCO + 6 + 9 + + + PLLSAIP + PLLSAI division factor for 48MHz + clock + 16 + 2 + + + PLLSAIQ + PLLSAI division factor for SAI + clock + 24 + 4 + + + + + DCKCFGR1 + DCKCFGR1 + dedicated clocks configuration + register + 0x8C + 0x20 + read-write + 0x20003000 + + + PLLI2SDIV + PLLI2S division factor for SAI1 + clock + 0 + 5 + + + PLLSAIDIVQ + PLLSAI division factor for SAI1 + clock + 8 + 5 + + + SAI1SEL + SAI1 clock source + selection + 20 + 2 + + + SAI2SEL + SAI2 clock source + selection + 22 + 2 + + + TIMPRE + Timers clocks prescalers + selection + 24 + 1 + + + + + DCKCFGR2 + DCKCFGR2 + dedicated clocks configuration + register + 0x90 + 0x20 + read-write + 0x20003000 + + + UART1SEL + USART 1 clock source + selection + 0 + 2 + + + UART2SEL + USART 2 clock source + selection + 2 + 2 + + + UART3SEL + USART 3 clock source + selection + 4 + 2 + + + UART4SEL + UART 4 clock source + selection + 6 + 2 + + + UART5SEL + UART 5 clock source + selection + 8 + 2 + + + UART6SEL + USART 6 clock source + selection + 10 + 2 + + + UART7SEL + UART 7 clock source + selection + 12 + 2 + + + UART8SEL + UART 8 clock source + selection + 14 + 2 + + + I2C1SEL + I2C1 clock source + selection + 16 + 2 + + + I2C2SEL + I2C2 clock source + selection + 18 + 2 + + + I2C3SEL + I2C3 clock source + selection + 20 + 2 + + + LPTIM1SEL + Low power timer 1 clock source + selection + 24 + 2 + + + CK48MSEL + 48MHz clock source + selection + 27 + 1 + + + SDMMC1SEL + SDMMC1 clock source + selection + 28 + 1 + + + SDMMC2SEL + SDMMC2 clock source + selection + 29 + 1 + + + + + + + SDMMC1 + Secure digital input/output + interface + SDMMC + 0x40012C00 + + 0x0 + 0x400 + registers + + + SDMMC1 + SDMMC1 global interrupt + 49 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal) + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 132 + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table 132 + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table 132 + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table 132 + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + SDMMC2 + 0x40011C00 + + + SAI1 + Serial audio interface + SAI + 0x40015800 + + 0x0 + 0x400 + registers + + + + BCR1 + BCR1 + BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MCKDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIXEN + Audio block B enable + 16 + 1 + + + OUTDRIV + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + BCR2 + BCR2 + BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + BFRCR + BFRCR + BFRCR + 0x2C + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + BSLOTR + BSLOTR + BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + BIM + BIM + BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDETIE + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + BSR + BSR + BStatus register + 0x38 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + BCLRFR + BCLRFR + BClear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + CLFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CCNRDY + Clear codec not ready flag + 4 + 1 + + + CWCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + CMUTEDET + Mute detection flag + 1 + 1 + + + COVRUDR + Clear overrun / underrun + 0 + 1 + + + + + BDR + BDR + BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + ACR1 + ACR1 + AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCKDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIXEN + Audio block A enable + 16 + 1 + + + OUTDRIV + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + ACR2 + ACR2 + AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + AFRCR + AFRCR + AFRCR + 0xC + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + ASLOTR + ASLOTR + ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + AIM + AIM + AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDETIE + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + ASR + ASR + AStatus register + 0x18 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + ACLRFR + ACLRFR + AClear flag register + 0x1C + 0x20 + write-only + 0x00000000 + + + CLFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. + 5 + 1 + + + CCNRDY + Clear codec not ready flag + 4 + 1 + + + CWCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + CMUTEDET + Mute detection flag + 1 + 1 + + + COVRUDR + Clear overrun / underrun + 0 + 1 + + + + + ADR + ADR + AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + GCR + GCR + Global configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + SYNCIN + Synchronization inputs + 0 + 2 + + + SYNCOUT + Synchronization outputs + 4 + 2 + + + + + + + SAI2 + 0x40015C00 + + SAI2 + SAI2 global interrupt + 91 + + + + SPI5 + Serial peripheral interface + SPI + 0x40015000 + + 0x0 + 0x400 + registers + + + SPI5 + SPI 5 global interrupt + 85 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + FRE + frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI1 + 0x40013000 + + SPI1 + SPI1 global interrupt + 35 + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI4 + 0x40013400 + + SPI4 + SPI 4 global interrupt + 84 + + + SAI1 + SAI1 global interrupt + 87 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRMP + MEMRMP + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_BOOT + Memory boot mapping + 0 + 1 + + + SWP_FMC + FMC memory mapping swap + 10 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + PB7_FMP + PB7_FMP Fast Mode + Enable + 5 + 1 + + + PB8_FMP + PB8_FMP Fast Mode + Enable + 6 + 1 + + + PB9_FMP + Fast Mode + Enable + 7 + 1 + + + ADCDC2 + ADC3DC2 + 16 + 3 + + + PB6_FMP + PB6_FMP Fast Mode + 4 + 1 + + + I2C3_FMP + I2C3_FMP I2C3 Fast Mode + + Enable + 2 + 1 + + + I2C2_FMP + I2C2_FMP I2C2 Fast Mode + + Enable + 1 + 1 + + + I2C1_FMP + I2C1_FMP I2C1 Fast Mode + + Enable + 0 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + USART3 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40004800 + + 0x0 + 0x400 + registers + + + USART3 + USART3 global interrupt + 39 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + M1 + Word length + 28 + 1 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT4 + Driver Enable assertion + time + 25 + 1 + + + DEAT3 + DEAT3 + 24 + 1 + + + DEAT2 + DEAT2 + 23 + 1 + + + DEAT1 + DEAT1 + 22 + 1 + + + DEAT0 + DEAT0 + 21 + 1 + + + DEDT4 + Driver Enable de-assertion + time + 20 + 1 + + + DEDT3 + DEDT3 + 19 + 1 + + + DEDT2 + DEDT2 + 18 + 1 + + + DEDT1 + DEDT1 + 17 + 1 + + + DEDT0 + DEDT0 + 16 + 1 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4_7 + Address of the USART node + 28 + 4 + + + ADD0_3 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD1 + Auto baud rate mode + 22 + 1 + + + ABRMOD0 + ABRMOD0 + 21 + 1 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + TAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + Ir low-power + 2 + 1 + + + IREN + Ir mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + TCBGTIE + Transmission complete before guard time + interrupt enable + 24 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + BRR + USARTDIV + 0 + 16 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + TEACK + TEACK + 21 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + ABRF + ABRF + 15 + 1 + + + ABRE + ABRE + 14 + 1 + + + EOBF + EOBF + 12 + 1 + + + RTOF + RTOF + 11 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + LBDF + LBDF + 8 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NF + NF + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + TCBGT + Transmission complete before guard time + completion + 25 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + CMCF + Character match clear flag + 17 + 1 + + + EOBCF + End of block clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + TCBGTCF + Transmission completed before guard time + clear flag + 7 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + + + USART6 + 0x40011400 + + USART6 + USART6 global interrupt + 71 + + + + UART8 + 0x40007C00 + + UART8 + UART 8 global interrupt + 83 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + UART7 + 0x40007800 + + UART7 + UART7 global interrupt + 82 + + + + UART4 + 0x40004C00 + + UART4 + UART4 global interrupt + 52 + + + SDMMC2 + SDMMC2 global interrupt + 103 + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011000 + + 0x0 + 0x400 + registers + + + USART1 + USART1 global interrupt + 37 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + M1 + Word length + 28 + 1 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT4 + Driver Enable assertion + time + 25 + 1 + + + DEAT3 + DEAT3 + 24 + 1 + + + DEAT2 + DEAT2 + 23 + 1 + + + DEAT1 + DEAT1 + 22 + 1 + + + DEAT0 + DEAT0 + 21 + 1 + + + DEDT4 + Driver Enable de-assertion + time + 20 + 1 + + + DEDT3 + DEDT3 + 19 + 1 + + + DEDT2 + DEDT2 + 18 + 1 + + + DEDT1 + DEDT1 + 17 + 1 + + + DEDT0 + DEDT0 + 16 + 1 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4_7 + Address of the USART node + 28 + 4 + + + ADD0_3 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD1 + Auto baud rate mode + 22 + 1 + + + ABRMOD0 + ABRMOD0 + 21 + 1 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + DATAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + Ir low-power + 2 + 1 + + + IREN + Ir mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + TCBGTIE + Transmission complete before guard time + interrupt enable + 24 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + BRR + USARTDIV + 0 + 16 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + TEACK + TEACK + 21 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + ABRF + ABRF + 15 + 1 + + + ABRE + ABRE + 14 + 1 + + + EOBF + EOBF + 12 + 1 + + + RTOF + RTOF + 11 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + LBDF + LBDF + 8 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NF + NF + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + TCBGT + Transmission complete before guard time + completion + 25 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + CMCF + Character match clear flag + 17 + 1 + + + EOBCF + End of block clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + TCBGTCF + Transmission completed before guard time + clear flag + 7 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + + OTG_FS_GOTGCTL + OTG_FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + VBVALOEN + VBUS valid override enable + 2 + 1 + read-write + + + VBVALOVAL + VBUS valid override value + 3 + 1 + read-write + + + AVALOEN + A-peripheral session valid override + enable + 4 + 1 + read-write + + + AVALOVAL + A-peripheral session valid override + value + 5 + 1 + read-write + + + BVALOEN + B-peripheral session valid override + enable + 6 + 1 + read-write + + + BVALOVAL + B-peripheral session valid override + value + 7 + 1 + read-write + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + OTGVER + OTG version + 20 + 1 + read-write + + + + + OTG_FS_GOTGINT + OTG_FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_FS_GAHBCFG + OTG_FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_FS_GUSBCFG + OTG_FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + + + OTG_FS_GRSTCTL + OTG_FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_FS_GINTSTS + OTG_FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + RSTDET + Reset detected interrupt + 23 + 1 + read-write + + + + + OTG_FS_GINTMSK + OTG_FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDETM + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMIN + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_FS_GRXSTSR_Device + OTG_FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSR_Host + OTG_FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + OTG_FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GRXFSIZ + OTG_FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_FS_DIEPTXF0_Device + OTG_FS_DIEPTXF0_Device + OTG_FS Endpoint 0 Transmit FIFO + size + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXFSIZ_Host + OTG_FS_HNPTXFSIZ_Host + OTG_FS Host non-periodic transmit FIFO size + register + OTG_FS_DIEPTXF0_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXSTS + OTG_FS_HNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + OTG_FS_GCCFG + OTG_FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_FS_CID + OTG_FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_FS_HPTXFSIZ + OTG_FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF1 + OTG_FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF2 + OTG_FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF3 + OTG_FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_GRXSTSP_Device + OTG_FS_GRXSTSP_Device + OTG status read and pop register (Device + mode) + 0x20 + 0x20 + read-only + 0x02000400 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSP_Host + OTG_FS_GRXSTSP_Host + OTG status read and pop register (Host + mode) + OTG_FS_GRXSTSP_Device + 0x20 + 0x20 + read-only + 0x02000400 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GI2CCTL + OTG_FS_GI2CCTL + OTG I2C access register + 0x30 + 0x20 + read-write + 0x02000400 + + + RWDATA + I2C Read/Write Data + 0 + 8 + + + REGADDR + I2C Register Address + 8 + 8 + + + ADDR + I2C Address + 16 + 7 + + + I2CEN + I2C Enable + 23 + 1 + + + ACK + I2C ACK + 24 + 1 + + + I2CDEVADR + I2C Device Address + 26 + 2 + + + I2CDATSE0 + I2C DatSe0 USB mode + 28 + 1 + + + RW + Read/Write Indicator + 30 + 1 + + + BSYDNE + I2C Busy/Done + 31 + 1 + + + + + OTG_FS_DIEPTXF4 + OTG_FS_DIEPTXF4 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF5 + OTG_FS_DIEPTXF5 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_GLPMCFG + OTG_FS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 0x20 + 0x02000400 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-write + + + REMWAKE + bRemoteWake value + 6 + 1 + read-write + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + + OTG_FS_HCFG + OTG_FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_FS_HFIR + OTG_FS_HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_FS_HFNUM + OTG_FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_FS_HPTXSTS + OTG_FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_FS_HAINT + OTG_FS_HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_FS_HAINTMSK + OTG_FS_HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_FS_HPRT + OTG_FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_FS_HCCHAR0 + OTG_FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR1 + OTG_FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR2 + OTG_FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR3 + OTG_FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR4 + OTG_FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR5 + OTG_FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR6 + OTG_FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR7 + OTG_FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT0 + OTG_FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT1 + OTG_FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT2 + OTG_FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT3 + OTG_FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT4 + OTG_FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT5 + OTG_FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT6 + OTG_FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT7 + OTG_FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK0 + OTG_FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK1 + OTG_FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK2 + OTG_FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK3 + OTG_FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK4 + OTG_FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK5 + OTG_FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK6 + OTG_FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK7 + OTG_FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ0 + OTG_FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ1 + OTG_FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ2 + OTG_FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ3 + OTG_FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ4 + OTG_FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ5 + OTG_FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ6 + OTG_FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ7 + OTG_FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR8 + OTG_FS_HCCHAR8 + OTG_FS host channel-8 characteristics + register + 0x200 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT8 + OTG_FS_HCINT8 + OTG_FS host channel-8 interrupt + register + 0x208 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK8 + OTG_FS_HCINTMSK8 + OTG_FS host channel-8 mask + register + 0x20C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ8 + OTG_FS_HCTSIZ8 + OTG_FS host channel-8 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR9 + OTG_FS_HCCHAR9 + OTG_FS host channel-9 characteristics + register + 0x220 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT9 + OTG_FS_HCINT9 + OTG_FS host channel-9 interrupt + register + 0x228 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK9 + OTG_FS_HCINTMSK9 + OTG_FS host channel-9 mask + register + 0x22C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ9 + OTG_FS_HCTSIZ9 + OTG_FS host channel-9 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR10 + OTG_FS_HCCHAR10 + OTG_FS host channel-10 characteristics + register + 0x240 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT10 + OTG_FS_HCINT10 + OTG_FS host channel-10 interrupt + register + 0x248 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK10 + OTG_FS_HCINTMSK10 + OTG_FS host channel-10 mask + register + 0x24C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ10 + OTG_FS_HCTSIZ10 + OTG_FS host channel-10 transfer size + register + 0x250 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR11 + OTG_FS_HCCHAR11 + OTG_FS host channel-11 characteristics + register + 0x260 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT11 + OTG_FS_HCINT11 + OTG_FS host channel-11 interrupt + register + 0x268 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK11 + OTG_FS_HCINTMSK11 + OTG_FS host channel-11 mask + register + 0x26C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ11 + OTG_FS_HCTSIZ11 + OTG_FS host channel-11 transfer size + register + 0x270 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + OTG_FS_DCFG + OTG_FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + OTG_FS_DCTL + OTG_FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_FS_DSTS + OTG_FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_FS_DIEPMSK + OTG_FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + OTG_FS_DOEPMSK + OTG_FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + OTG_FS_DAINT + OTG_FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DAINTMSK + OTG_FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DVBUSDIS + OTG_FS_DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_FS_DVBUSPULSE + OTG_FS_DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_FS_DIEPEMPMSK + OTG_FS_DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_FS_DIEPCTL0 + OTG_FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + OTG_FS_DIEPCTL1 + OTG_FS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL2 + OTG_FS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL3 + OTG_FS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL0 + OTG_FS_DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + OTG_FS_DOEPCTL1 + OTG_FS_DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL2 + OTG_FS_DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL3 + OTG_FS_DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT0 + OTG_FS_DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT1 + OTG_FS_DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT2 + OTG_FS_DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT3 + OTG_FS_DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DOEPINT0 + OTG_FS_DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT1 + OTG_FS_DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT2 + OTG_FS_DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT3 + OTG_FS_DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DIEPTSIZ0 + OTG_FS_DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DOEPTSIZ0 + OTG_FS_DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DIEPTSIZ1 + OTG_FS_DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ2 + OTG_FS_DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ3 + OTG_FS_DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS0 + OTG_FS_DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS1 + OTG_FS_DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS2 + OTG_FS_DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS3 + OTG_FS_DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPTSIZ1 + OTG_FS_DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ2 + OTG_FS_DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ3 + OTG_FS_DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPCTL4 + OTG_FS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT4 + OTG_FS_DIEPINT4 + device endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ4 + OTG_FS_DIEPTSIZ4 + device endpoint-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS4 + OTG_FS_DTXFSTS4 + OTG_FS device IN endpoint transmit FIFO + status register + 0x198 + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DIEPCTL5 + OTG_FS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT5 + OTG_FS_DIEPINT5 + device endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ5 + OTG_FS_DIEPTSIZ5 + device endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS5 + OTG_FS_DTXFSTS5 + OTG_FS device IN endpoint transmit FIFO + status register + 0x1B8 + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPCTL4 + OTG_FS_DOEPCTL4 + device endpoint-4 control + register + 0x380 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT4 + OTG_FS_DOEPINT4 + device endpoint-4 interrupt + register + 0x388 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ4 + OTG_FS_DOEPTSIZ4 + device OUT endpoint-4 transfer size + register + 0x390 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPCTL5 + OTG_FS_DOEPCTL5 + device endpoint-5 control + register + 0x3A0 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT5 + OTG_FS_DOEPINT5 + device endpoint-5 interrupt + register + 0x3A8 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ5 + OTG_FS_DOEPTSIZ5 + device OUT endpoint-5 transfer size + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + + OTG_FS_PCGCCTL + OTG_FS_PCGCCTL + OTG_FS power and clock gating control + register (OTG_FS_PCGCCTL) + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR12 + OTG_HS_HCCHAR12 + OTG_HS host channel-12 characteristics + register + 0x280 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT12 + OTG_HS_HCSPLT12 + OTG_HS host channel-12 split control + register + 0x284 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT12 + OTG_HS_HCINT12 + OTG_HS host channel-12 interrupt + register + 0x288 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK12 + OTG_HS_HCINTMSK12 + OTG_HS host channel-12 interrupt mask + register + 0x28C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ12 + OTG_HS_HCTSIZ12 + OTG_HS host channel-12 transfer size + register + 0x290 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA12 + OTG_HS_HCDMA12 + OTG_HS host channel-12 DMA address + register + 0x294 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR13 + OTG_HS_HCCHAR13 + OTG_HS host channel-13 characteristics + register + 0x2A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT13 + OTG_HS_HCSPLT13 + OTG_HS host channel-13 split control + register + 0x2A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT13 + OTG_HS_HCINT13 + OTG_HS host channel-13 interrupt + register + 0x2A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK13 + OTG_HS_HCINTMSK13 + OTG_HS host channel-13 interrupt mask + register + 0x2AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALLM response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ13 + OTG_HS_HCTSIZ13 + OTG_HS host channel-13 transfer size + register + 0x2B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA13 + OTG_HS_HCDMA13 + OTG_HS host channel-13 DMA address + register + 0x2B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR14 + OTG_HS_HCCHAR14 + OTG_HS host channel-14 characteristics + register + 0x2C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT14 + OTG_HS_HCSPLT14 + OTG_HS host channel-14 split control + register + 0x2C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT14 + OTG_HS_HCINT14 + OTG_HS host channel-14 interrupt + register + 0x2C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK14 + OTG_HS_HCINTMSK14 + OTG_HS host channel-14 interrupt mask + register + 0x2CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAKM response received interrupt + mask + 4 + 1 + + + ACKM + ACKM response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ14 + OTG_HS_HCTSIZ14 + OTG_HS host channel-14 transfer size + register + 0x2D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA14 + OTG_HS_HCDMA14 + OTG_HS host channel-14 DMA address + register + 0x2D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR15 + OTG_HS_HCCHAR15 + OTG_HS host channel-15 characteristics + register + 0x2E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT15 + OTG_HS_HCSPLT15 + OTG_HS host channel-15 split control + register + 0x2E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT15 + OTG_HS_HCINT15 + OTG_HS host channel-15 interrupt + register + 0x2E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK15 + OTG_HS_HCINTMSK15 + OTG_HS host channel-15 interrupt mask + register + 0x2EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ15 + OTG_HS_HCTSIZ15 + OTG_HS host channel-15 transfer size + register + 0x2F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA15 + OTG_HS_HCDMA15 + OTG_HS host channel-15 DMA address + register + 0x2F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + OTG_HS_EP1_OUT + USB On The Go HS End Point 1 Out + 74 + + + OTG_HS_EP1_IN + USB On The Go HS End Point 1 In + 75 + + + OTG_HS_WKUP + USB On The Go HS Wakeup through + 76 + + + OTG_HS + USB On The Go HS global + interrupt + 77 + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + DMAREQ + DMA request signal enabled for USB OTG + HS + 30 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDE + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMINTM + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_HNPTXFSIZ_Host + OTG_HS_HNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF0_Device + OTG_HS_DIEPTXF0_Device + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_HNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_HNPTXSTS + OTG_HS_HNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x10C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x110 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x114 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x118 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Device + OTG_HS_GRXSTSR_Device + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Device + OTG_HS_GRXSTSP_Device + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GLPMCFG + OTG_HS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 32 + 0x0 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-only + + + REMWAKE + bRemoteWake value + 6 + 1 + read-only + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + OTG_HS_GI2CCTL + OTG_HS_GI2CCTL + OTG I2C access register + 0x30 + 32 + read-write + 0x00000000 + + + BSYDNE + I2C Busy/Done + 31 + 1 + + + RW + Read/Write Indicator + 30 + 1 + + + I2CDATSE0 + I2C DatSe0 USB mode + 28 + 1 + + + I2CDEVADR + I2C Device Address + 26 + 2 + + + ACK + I2C ACK + 24 + 1 + + + I2CEN + I2C Enable + 23 + 1 + + + ADDR + I2C Address + 16 + 7 + + + REGADDR + I2C Register Address + 8 + 8 + + + RWDATA + I2C Read/Write Data + 0 + 8 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x500 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA0 + OTG_HS_DIEPDMA0 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-0 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-1 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-2 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-3 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-4 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ6 + OTG_HS_DIEPTSIZ6 + OTG_HS device endpoint transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS6 + OTG_HS_DTXFSTS6 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1D8 + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ7 + OTG_HS_DIEPTSIZ7 + OTG_HS device endpoint transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS7 + OTG_HS_DTXFSTS7 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1F8 + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DOEPCTL4 + OTG_HS_DOEPCTL4 + OTG device endpoint-4 control + register + 0x380 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL5 + OTG_HS_DOEPCTL5 + OTG device endpoint-5 control + register + 0x3A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL6 + OTG_HS_DOEPCTL6 + OTG device endpoint-6 control + register + 0x3C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL7 + OTG_HS_DOEPCTL7 + OTG device endpoint-7 control + register + 0x3E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPTSIZ5 + OTG_HS_DOEPTSIZ5 + OTG_HS device endpoint-5 transfer size + register + 0x3B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ6 + OTG_HS_DOEPTSIZ6 + OTG_HS device endpoint-6 transfer size + register + 0x3D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ7 + OTG_HS_DOEPTSIZ7 + OTG_HS device endpoint-7 transfer size + register + 0x3F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPDMA0 + OTG_HS_DOEPDMA0 + OTG Device channel-x DMA address + register + 0x314 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA1 + OTG_HS_DOEPDMA1 + OTG Device channel-x DMA address + register + 0x334 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA2 + OTG_HS_DOEPDMA2 + OTG Device channel-x DMA address + register + 0x354 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA3 + OTG_HS_DOEPDMA3 + OTG Device channel-x DMA address + register + 0x374 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA4 + OTG_HS_DOEPDMA4 + OTG Device channel-x DMA address + register + 0x394 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA5 + OTG_HS_DOEPDMA5 + OTG Device channel-x DMA address + register + 0x3B4 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA6 + OTG_HS_DOEPDMA6 + OTG Device channel-x DMA address + register + 0x3D4 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA7 + OTG_HS_DOEPDMA7 + OTG Device channel-x DMA address + register + 0x3F4 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA8 + OTG_HS_DOEPDMA8 + OTG Device channel-x DMA address + register + 0x414 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA9 + OTG_HS_DOEPDMA9 + OTG Device channel-x DMA address + register + 0x434 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA10 + OTG_HS_DOEPDMA10 + OTG Device channel-x DMA address + register + 0x454 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA11 + OTG_HS_DOEPDMA11 + OTG Device channel-x DMA address + register + 0x474 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA12 + OTG_HS_DOEPDMA12 + OTG Device channel-x DMA address + register + 0x494 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA13 + OTG_HS_DOEPDMA13 + OTG Device channel-x DMA address + register + 0x4B4 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA14 + OTG_HS_DOEPDMA14 + OTG Device channel-x DMA address + register + 0x4D4 + 32 + read-write + 0x00000000 + + + OTG_HS_DOEPDMA15 + OTG_HS_DOEPDMA15 + OTG Device channel-x DMA address + register + 0x4F4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG Device channel-x DMA address + register + 0x1B4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA6 + OTG_HS_DIEPDMA6 + OTG Device channel-x DMA address + register + 0x1D4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA7 + OTG_HS_DIEPDMA7 + OTG Device channel-x DMA address + register + 0x1F4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA8 + OTG_HS_DIEPDMA8 + OTG Device channel-x DMA address + register + 0x214 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA9 + OTG_HS_DIEPDMA9 + OTG Device channel-x DMA address + register + 0x234 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA10 + OTG_HS_DIEPDMA10 + OTG Device channel-x DMA address + register + 0x254 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA11 + OTG_HS_DIEPDMA11 + OTG Device channel-x DMA address + register + 0x274 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA12 + OTG_HS_DIEPDMA12 + OTG Device channel-x DMA address + register + 0x294 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA13 + OTG_HS_DIEPDMA13 + OTG Device channel-x DMA address + register + 0x2B4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA14 + OTG_HS_DIEPDMA14 + OTG Device channel-x DMA address + register + 0x2D4 + 32 + read-write + 0x00000000 + + + OTG_HS_DIEPDMA15 + OTG_HS_DIEPDMA15 + OTG Device channel-x DMA address + register + 0x2F4 + 32 + read-write + 0x00000000 + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CSR + CSR + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + RVR + RVR + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + CVR + CVR + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISFOLD + DISFOLD + 2 + 1 + + + FPEXCODIS + FPEXCODIS + 10 + 1 + + + DISRAMODE + DISRAMODE + 11 + 1 + + + DISITMATBFLUSH + DISITMATBFLUSH + 12 + 1 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + DC + DC + 16 + 1 + + + IC + IC + 17 + 1 + + + BP + BP + 18 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + IACCVIOL + 0 + 1 + + + DACCVIOL + DACCVIOL + 1 + 1 + + + MUNSTKERR + MUNSTKERR + 3 + 1 + + + MSTKERR + MSTKERR + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + MMARVALID + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Bus fault address + 0 + 32 + + + + + + + PF + Processor features + PF + 0xE000ED78 + + 0x0 + 0xD + registers + + + + CLIDR + CLIDR + Cache Level ID register + 0x0 + 0x20 + read-only + 0x09000003 + + + CL1 + CL1 + 0 + 3 + + + CL2 + CL2 + 3 + 3 + + + CL3 + CL3 + 6 + 3 + + + CL4 + CL4 + 9 + 3 + + + CL5 + CL5 + 12 + 3 + + + CL6 + CL6 + 15 + 3 + + + CL7 + CL7 + 18 + 3 + + + LoUIS + LoUIS + 21 + 3 + + + LoC + LoC + 24 + 3 + + + LoU + LoU + 27 + 3 + + + + + CTR + CTR + Cache Type register + 0x4 + 0x20 + read-only + 0X8303C003 + + + _IminLine + IminLine + 0 + 4 + + + DMinLine + DMinLine + 16 + 4 + + + ERG + ERG + 20 + 4 + + + CWG + CWG + 24 + 4 + + + Format + Format + 29 + 3 + + + + + CCSIDR + CCSIDR + Cache Size ID register + 0x8 + 0x20 + read-only + 0X00000000 + + + LineSize + LineSize + 0 + 3 + + + Associativity + Associativity + 3 + 10 + + + NumSets + NumSets + 13 + 15 + + + WA + WA + 28 + 1 + + + RA + RA + 29 + 1 + + + WB + WB + 30 + 1 + + + WT + WT + 31 + 1 + + + + + + + AC + Access control + AC + 0xE000EF90 + + 0x0 + 0x1D + registers + + + + ITCMCR + ITCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x0 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + DTCMCR + DTCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x4 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + AHBPCR + AHBPCR + AHBP Control register + 0x8 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + SZ + SZ + 1 + 3 + + + + + CACR + CACR + Auxiliary Cache Control + register + 0xC + 0x20 + read-write + 0X00000000 + + + SIWT + SIWT + 0 + 1 + + + ECCEN + ECCEN + 1 + 1 + + + FORCEWT + FORCEWT + 2 + 1 + + + + + AHBSCR + AHBSCR + AHB Slave Control register + 0x10 + 0x20 + read-write + 0X00000000 + + + CTL + CTL + 0 + 2 + + + TPRI + TPRI + 2 + 9 + + + INITCOUNT + INITCOUNT + 11 + 5 + + + + + ABFSR + ABFSR + Auxiliary Bus Fault Status + register + 0x18 + 0x20 + read-write + 0X00000000 + + + ITCM + ITCM + 0 + 1 + + + DTCM + DTCM + 1 + 1 + + + AHBP + AHBP + 2 + 1 + + + AXIM + AXIM + 3 + 1 + + + EPPB + EPPB + 4 + 1 + + + AXIMTYPE + AXIMTYPE + 8 + 2 + + + + + + + diff --git a/dev/svd/STM32F7x5.svd b/dev/svd/STM32F7x5.svd new file mode 100644 index 00000000000..7f14b7c3aa1 --- /dev/null +++ b/dev/svd/STM32F7x5.svd @@ -0,0 +1,71136 @@ + + + STM32F7x5 + 1.4 + STM32F7x5 + + + CM7 + r0p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + RNG + Random number generator + RNG + 0x50060800 + + 0x0 + 0x400 + registers + + + HASH_RNG + Hash and Rng global interrupt + 80 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + IE + Interrupt enable + 3 + 1 + + + RNGEN + Random number generator + enable + 2 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + 0x00000000 + + + SEIS + Seed error interrupt + status + 6 + 1 + read-write + + + CEIS + Clock error interrupt + status + 5 + 1 + read-write + + + SECS + Seed error current status + 2 + 1 + read-only + + + CECS + Clock error current status + 1 + 1 + read-only + + + DRDY + Data ready + 0 + 1 + read-only + + + + + DR + DR + data register + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data + 0 + 32 + + + + + + + HASH + Hash processor + HASH + 0x50060400 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + INIT + Initialize message digest + calculation + 2 + 1 + write-only + + + DMAE + DMA enable + 3 + 1 + read-write + + + DATATYPE + Data type selection + 4 + 2 + read-write + + + MODE + Mode selection + 6 + 1 + read-write + + + ALGO0 + Algorithm selection + 7 + 1 + read-write + + + NBW + Number of words already + pushed + 8 + 4 + read-only + + + DINNE + DIN not empty + 12 + 1 + read-only + + + MDMAT + Multiple DMA Transfers + 13 + 1 + read-write + + + LKEY + Long key selection + 16 + 1 + read-write + + + ALGO1 + ALGO + 18 + 1 + read-write + + + + + DIN + DIN + data input register + 0x4 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + STR + STR + start register + 0x8 + 0x20 + 0x00000000 + + + DCAL + Digest calculation + 8 + 1 + write-only + + + NBLW + Number of valid bits in the last word of + the message + 0 + 5 + read-write + + + + + HR0 + HR0 + digest registers + 0xC + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HR1 + HR1 + digest registers + 0x10 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HR2 + HR2 + digest registers + 0x14 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HR3 + HR3 + digest registers + 0x18 + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HR4 + HR4 + digest registers + 0x1C + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + IMR + IMR + interrupt enable register + 0x20 + 0x20 + read-write + 0x00000000 + + + DCIE + Digest calculation completion interrupt + enable + 1 + 1 + + + DINIE + Data input interrupt + enable + 0 + 1 + + + + + SR + SR + status register + 0x24 + 0x20 + 0x00000001 + + + BUSY + Busy bit + 3 + 1 + read-only + + + DMAS + DMA Status + 2 + 1 + read-only + + + DCIS + Digest calculation completion interrupt + status + 1 + 1 + read-write + + + DINIS + Data input interrupt + status + 0 + 1 + read-write + + + + + CSR0 + CSR0 + context swap registers + 0xF8 + 0x20 + read-write + 0x00000000 + + + CSR0 + CSR0 + 0 + 32 + + + + + CSR1 + CSR1 + context swap registers + 0xFC + 0x20 + read-write + 0x00000000 + + + CSR1 + CSR1 + 0 + 32 + + + + + CSR2 + CSR2 + context swap registers + 0x100 + 0x20 + read-write + 0x00000000 + + + CSR2 + CSR2 + 0 + 32 + + + + + CSR3 + CSR3 + context swap registers + 0x104 + 0x20 + read-write + 0x00000000 + + + CSR3 + CSR3 + 0 + 32 + + + + + CSR4 + CSR4 + context swap registers + 0x108 + 0x20 + read-write + 0x00000000 + + + CSR4 + CSR4 + 0 + 32 + + + + + CSR5 + CSR5 + context swap registers + 0x10C + 0x20 + read-write + 0x00000000 + + + CSR5 + CSR5 + 0 + 32 + + + + + CSR6 + CSR6 + context swap registers + 0x110 + 0x20 + read-write + 0x00000000 + + + CSR6 + CSR6 + 0 + 32 + + + + + CSR7 + CSR7 + context swap registers + 0x114 + 0x20 + read-write + 0x00000000 + + + CSR7 + CSR7 + 0 + 32 + + + + + CSR8 + CSR8 + context swap registers + 0x118 + 0x20 + read-write + 0x00000000 + + + CSR8 + CSR8 + 0 + 32 + + + + + CSR9 + CSR9 + context swap registers + 0x11C + 0x20 + read-write + 0x00000000 + + + CSR9 + CSR9 + 0 + 32 + + + + + CSR10 + CSR10 + context swap registers + 0x120 + 0x20 + read-write + 0x00000000 + + + CSR10 + CSR10 + 0 + 32 + + + + + CSR11 + CSR11 + context swap registers + 0x124 + 0x20 + read-write + 0x00000000 + + + CSR11 + CSR11 + 0 + 32 + + + + + CSR12 + CSR12 + context swap registers + 0x128 + 0x20 + read-write + 0x00000000 + + + CSR12 + CSR12 + 0 + 32 + + + + + CSR13 + CSR13 + context swap registers + 0x12C + 0x20 + read-write + 0x00000000 + + + CSR13 + CSR13 + 0 + 32 + + + + + CSR14 + CSR14 + context swap registers + 0x130 + 0x20 + read-write + 0x00000000 + + + CSR14 + CSR14 + 0 + 32 + + + + + CSR15 + CSR15 + context swap registers + 0x134 + 0x20 + read-write + 0x00000000 + + + CSR15 + CSR15 + 0 + 32 + + + + + CSR16 + CSR16 + context swap registers + 0x138 + 0x20 + read-write + 0x00000000 + + + CSR16 + CSR16 + 0 + 32 + + + + + CSR17 + CSR17 + context swap registers + 0x13C + 0x20 + read-write + 0x00000000 + + + CSR17 + CSR17 + 0 + 32 + + + + + CSR18 + CSR18 + context swap registers + 0x140 + 0x20 + read-write + 0x00000000 + + + CSR18 + CSR18 + 0 + 32 + + + + + CSR19 + CSR19 + context swap registers + 0x144 + 0x20 + read-write + 0x00000000 + + + CSR19 + CSR19 + 0 + 32 + + + + + CSR20 + CSR20 + context swap registers + 0x148 + 0x20 + read-write + 0x00000000 + + + CSR20 + CSR20 + 0 + 32 + + + + + CSR21 + CSR21 + context swap registers + 0x14C + 0x20 + read-write + 0x00000000 + + + CSR21 + CSR21 + 0 + 32 + + + + + CSR22 + CSR22 + context swap registers + 0x150 + 0x20 + read-write + 0x00000000 + + + CSR22 + CSR22 + 0 + 32 + + + + + CSR23 + CSR23 + context swap registers + 0x154 + 0x20 + read-write + 0x00000000 + + + CSR23 + CSR23 + 0 + 32 + + + + + CSR24 + CSR24 + context swap registers + 0x158 + 0x20 + read-write + 0x00000000 + + + CSR24 + CSR24 + 0 + 32 + + + + + CSR25 + CSR25 + context swap registers + 0x15C + 0x20 + read-write + 0x00000000 + + + CSR25 + CSR25 + 0 + 32 + + + + + CSR26 + CSR26 + context swap registers + 0x160 + 0x20 + read-write + 0x00000000 + + + CSR26 + CSR26 + 0 + 32 + + + + + CSR27 + CSR27 + context swap registers + 0x164 + 0x20 + read-write + 0x00000000 + + + CSR27 + CSR27 + 0 + 32 + + + + + CSR28 + CSR28 + context swap registers + 0x168 + 0x20 + read-write + 0x00000000 + + + CSR28 + CSR28 + 0 + 32 + + + + + CSR29 + CSR29 + context swap registers + 0x16C + 0x20 + read-write + 0x00000000 + + + CSR29 + CSR29 + 0 + 32 + + + + + CSR30 + CSR30 + context swap registers + 0x170 + 0x20 + read-write + 0x00000000 + + + CSR30 + CSR30 + 0 + 32 + + + + + CSR31 + CSR31 + context swap registers + 0x174 + 0x20 + read-write + 0x00000000 + + + CSR31 + CSR31 + 0 + 32 + + + + + CSR32 + CSR32 + context swap registers + 0x178 + 0x20 + read-write + 0x00000000 + + + CSR32 + CSR32 + 0 + 32 + + + + + CSR33 + CSR33 + context swap registers + 0x17C + 0x20 + read-write + 0x00000000 + + + CSR33 + CSR33 + 0 + 32 + + + + + CSR34 + CSR34 + context swap registers + 0x180 + 0x20 + read-write + 0x00000000 + + + CSR34 + CSR34 + 0 + 32 + + + + + CSR35 + CSR35 + context swap registers + 0x184 + 0x20 + read-write + 0x00000000 + + + CSR35 + CSR35 + 0 + 32 + + + + + CSR36 + CSR36 + context swap registers + 0x188 + 0x20 + read-write + 0x00000000 + + + CSR36 + CSR36 + 0 + 32 + + + + + CSR37 + CSR37 + context swap registers + 0x18C + 0x20 + read-write + 0x00000000 + + + CSR37 + CSR37 + 0 + 32 + + + + + CSR38 + CSR38 + context swap registers + 0x190 + 0x20 + read-write + 0x00000000 + + + CSR38 + CSR38 + 0 + 32 + + + + + CSR39 + CSR39 + context swap registers + 0x194 + 0x20 + read-write + 0x00000000 + + + CSR39 + CSR39 + 0 + 32 + + + + + CSR40 + CSR40 + context swap registers + 0x198 + 0x20 + read-write + 0x00000000 + + + CSR40 + CSR40 + 0 + 32 + + + + + CSR41 + CSR41 + context swap registers + 0x19C + 0x20 + read-write + 0x00000000 + + + CSR41 + CSR41 + 0 + 32 + + + + + CSR42 + CSR42 + context swap registers + 0x1A0 + 0x20 + read-write + 0x00000000 + + + CSR42 + CSR42 + 0 + 32 + + + + + CSR43 + CSR43 + context swap registers + 0x1A4 + 0x20 + read-write + 0x00000000 + + + CSR43 + CSR43 + 0 + 32 + + + + + CSR44 + CSR44 + context swap registers + 0x1A8 + 0x20 + read-write + 0x00000000 + + + CSR44 + CSR44 + 0 + 32 + + + + + CSR45 + CSR45 + context swap registers + 0x1AC + 0x20 + read-write + 0x00000000 + + + CSR45 + CSR45 + 0 + 32 + + + + + CSR46 + CSR46 + context swap registers + 0x1B0 + 0x20 + read-write + 0x00000000 + + + CSR46 + CSR46 + 0 + 32 + + + + + CSR47 + CSR47 + context swap registers + 0x1B4 + 0x20 + read-write + 0x00000000 + + + CSR47 + CSR47 + 0 + 32 + + + + + CSR48 + CSR48 + context swap registers + 0x1B8 + 0x20 + read-write + 0x00000000 + + + CSR48 + CSR48 + 0 + 32 + + + + + CSR49 + CSR49 + context swap registers + 0x1BC + 0x20 + read-write + 0x00000000 + + + CSR49 + CSR49 + 0 + 32 + + + + + CSR50 + CSR50 + context swap registers + 0x1C0 + 0x20 + read-write + 0x00000000 + + + CSR50 + CSR50 + 0 + 32 + + + + + CSR51 + CSR51 + context swap registers + 0x1C4 + 0x20 + read-write + 0x00000000 + + + CSR51 + CSR51 + 0 + 32 + + + + + CSR52 + CSR52 + context swap registers + 0x1C8 + 0x20 + read-write + 0x00000000 + + + CSR52 + CSR52 + 0 + 32 + + + + + CSR53 + CSR53 + context swap registers + 0x1CC + 0x20 + read-write + 0x00000000 + + + CSR53 + CSR53 + 0 + 32 + + + + + HASH_HR0 + HASH_HR0 + HASH digest register + 0x310 + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HASH_HR1 + HASH_HR1 + read-only + 0x314 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HASH_HR2 + HASH_HR2 + read-only + 0x318 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HASH_HR3 + HASH_HR3 + read-only + 0x31C + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HASH_HR4 + HASH_HR4 + read-only + 0x320 + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + HASH_HR5 + HASH_HR5 + read-only + 0x324 + 0x20 + read-only + 0x00000000 + + + H5 + H5 + 0 + 32 + + + + + HASH_HR6 + HASH_HR6 + read-only + 0x328 + 0x20 + read-only + 0x00000000 + + + H6 + H6 + 0 + 32 + + + + + HASH_HR7 + HASH_HR7 + read-only + 0x32C + 0x20 + read-only + 0x00000000 + + + H7 + H7 + 0 + 32 + + + + + + + CRYP + Cryptographic processor + CRYP + 0x50060000 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + ALGODIR + Algorithm direction + 2 + 1 + read-write + + + ALGOMODE0 + Algorithm mode + 3 + 3 + read-write + + + DATATYPE + Data type selection + 6 + 2 + read-write + + + KEYSIZE + Key size selection (AES mode + only) + 8 + 2 + read-write + + + FFLUSH + FIFO flush + 14 + 1 + write-only + + + CRYPEN + Cryptographic processor + enable + 15 + 1 + read-write + + + GCM_CCMPH + GCM_CCMPH + 16 + 2 + read-write + + + ALGOMODE3 + ALGOMODE + 19 + 1 + read-write + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x00000003 + + + BUSY + Busy bit + 4 + 1 + + + OFFU + Output FIFO full + 3 + 1 + + + OFNE + Output FIFO not empty + 2 + 1 + + + IFNF + Input FIFO not full + 1 + 1 + + + IFEM + Input FIFO empty + 0 + 1 + + + + + DIN + DIN + data input register + 0x8 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + DOUT + DOUT + data output register + 0xC + 0x20 + read-only + 0x00000000 + + + DATAOUT + Data output + 0 + 32 + + + + + DMACR + DMACR + DMA control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DOEN + DMA output enable + 1 + 1 + + + DIEN + DMA input enable + 0 + 1 + + + + + IMSCR + IMSCR + interrupt mask set/clear + register + 0x14 + 0x20 + read-write + 0x00000000 + + + OUTIM + Output FIFO service interrupt + mask + 1 + 1 + + + INIM + Input FIFO service interrupt + mask + 0 + 1 + + + + + RISR + RISR + raw interrupt status register + 0x18 + 0x20 + read-only + 0x00000001 + + + OUTRIS + Output FIFO service raw interrupt + status + 1 + 1 + + + INRIS + Input FIFO service raw interrupt + status + 0 + 1 + + + + + MISR + MISR + masked interrupt status + register + 0x1C + 0x20 + read-only + 0x00000000 + + + OUTMIS + Output FIFO service masked interrupt + status + 1 + 1 + + + INMIS + Input FIFO service masked interrupt + status + 0 + 1 + + + + + K0LR + K0LR + key registers + 0x20 + 0x20 + write-only + 0x00000000 + + + b224 + b224 + 0 + 1 + + + b225 + b225 + 1 + 1 + + + b226 + b226 + 2 + 1 + + + b227 + b227 + 3 + 1 + + + b228 + b228 + 4 + 1 + + + b229 + b229 + 5 + 1 + + + b230 + b230 + 6 + 1 + + + b231 + b231 + 7 + 1 + + + b232 + b232 + 8 + 1 + + + b233 + b233 + 9 + 1 + + + b234 + b234 + 10 + 1 + + + b235 + b235 + 11 + 1 + + + b236 + b236 + 12 + 1 + + + b237 + b237 + 13 + 1 + + + b238 + b238 + 14 + 1 + + + b239 + b239 + 15 + 1 + + + b240 + b240 + 16 + 1 + + + b241 + b241 + 17 + 1 + + + b242 + b242 + 18 + 1 + + + b243 + b243 + 19 + 1 + + + b244 + b244 + 20 + 1 + + + b245 + b245 + 21 + 1 + + + b246 + b246 + 22 + 1 + + + b247 + b247 + 23 + 1 + + + b248 + b248 + 24 + 1 + + + b249 + b249 + 25 + 1 + + + b250 + b250 + 26 + 1 + + + b251 + b251 + 27 + 1 + + + b252 + b252 + 28 + 1 + + + b253 + b253 + 29 + 1 + + + b254 + b254 + 30 + 1 + + + b255 + b255 + 31 + 1 + + + + + K0RR + K0RR + key registers + 0x24 + 0x20 + write-only + 0x00000000 + + + b192 + b192 + 0 + 1 + + + b193 + b193 + 1 + 1 + + + b194 + b194 + 2 + 1 + + + b195 + b195 + 3 + 1 + + + b196 + b196 + 4 + 1 + + + b197 + b197 + 5 + 1 + + + b198 + b198 + 6 + 1 + + + b199 + b199 + 7 + 1 + + + b200 + b200 + 8 + 1 + + + b201 + b201 + 9 + 1 + + + b202 + b202 + 10 + 1 + + + b203 + b203 + 11 + 1 + + + b204 + b204 + 12 + 1 + + + b205 + b205 + 13 + 1 + + + b206 + b206 + 14 + 1 + + + b207 + b207 + 15 + 1 + + + b208 + b208 + 16 + 1 + + + b209 + b209 + 17 + 1 + + + b210 + b210 + 18 + 1 + + + b211 + b211 + 19 + 1 + + + b212 + b212 + 20 + 1 + + + b213 + b213 + 21 + 1 + + + b214 + b214 + 22 + 1 + + + b215 + b215 + 23 + 1 + + + b216 + b216 + 24 + 1 + + + b217 + b217 + 25 + 1 + + + b218 + b218 + 26 + 1 + + + b219 + b219 + 27 + 1 + + + b220 + b220 + 28 + 1 + + + b221 + b221 + 29 + 1 + + + b222 + b222 + 30 + 1 + + + b223 + b223 + 31 + 1 + + + + + K1LR + K1LR + key registers + 0x28 + 0x20 + write-only + 0x00000000 + + + b160 + b160 + 0 + 1 + + + b161 + b161 + 1 + 1 + + + b162 + b162 + 2 + 1 + + + b163 + b163 + 3 + 1 + + + b164 + b164 + 4 + 1 + + + b165 + b165 + 5 + 1 + + + b166 + b166 + 6 + 1 + + + b167 + b167 + 7 + 1 + + + b168 + b168 + 8 + 1 + + + b169 + b169 + 9 + 1 + + + b170 + b170 + 10 + 1 + + + b171 + b171 + 11 + 1 + + + b172 + b172 + 12 + 1 + + + b173 + b173 + 13 + 1 + + + b174 + b174 + 14 + 1 + + + b175 + b175 + 15 + 1 + + + b176 + b176 + 16 + 1 + + + b177 + b177 + 17 + 1 + + + b178 + b178 + 18 + 1 + + + b179 + b179 + 19 + 1 + + + b180 + b180 + 20 + 1 + + + b181 + b181 + 21 + 1 + + + b182 + b182 + 22 + 1 + + + b183 + b183 + 23 + 1 + + + b184 + b184 + 24 + 1 + + + b185 + b185 + 25 + 1 + + + b186 + b186 + 26 + 1 + + + b187 + b187 + 27 + 1 + + + b188 + b188 + 28 + 1 + + + b189 + b189 + 29 + 1 + + + b190 + b190 + 30 + 1 + + + b191 + b191 + 31 + 1 + + + + + K1RR + K1RR + key registers + 0x2C + 0x20 + write-only + 0x00000000 + + + b128 + b128 + 0 + 1 + + + b129 + b129 + 1 + 1 + + + b130 + b130 + 2 + 1 + + + b131 + b131 + 3 + 1 + + + b132 + b132 + 4 + 1 + + + b133 + b133 + 5 + 1 + + + b134 + b134 + 6 + 1 + + + b135 + b135 + 7 + 1 + + + b136 + b136 + 8 + 1 + + + b137 + b137 + 9 + 1 + + + b138 + b138 + 10 + 1 + + + b139 + b139 + 11 + 1 + + + b140 + b140 + 12 + 1 + + + b141 + b141 + 13 + 1 + + + b142 + b142 + 14 + 1 + + + b143 + b143 + 15 + 1 + + + b144 + b144 + 16 + 1 + + + b145 + b145 + 17 + 1 + + + b146 + b146 + 18 + 1 + + + b147 + b147 + 19 + 1 + + + b148 + b148 + 20 + 1 + + + b149 + b149 + 21 + 1 + + + b150 + b150 + 22 + 1 + + + b151 + b151 + 23 + 1 + + + b152 + b152 + 24 + 1 + + + b153 + b153 + 25 + 1 + + + b154 + b154 + 26 + 1 + + + b155 + b155 + 27 + 1 + + + b156 + b156 + 28 + 1 + + + b157 + b157 + 29 + 1 + + + b158 + b158 + 30 + 1 + + + b159 + b159 + 31 + 1 + + + + + K2LR + K2LR + key registers + 0x30 + 0x20 + write-only + 0x00000000 + + + b96 + b96 + 0 + 1 + + + b97 + b97 + 1 + 1 + + + b98 + b98 + 2 + 1 + + + b99 + b99 + 3 + 1 + + + b100 + b100 + 4 + 1 + + + b101 + b101 + 5 + 1 + + + b102 + b102 + 6 + 1 + + + b103 + b103 + 7 + 1 + + + b104 + b104 + 8 + 1 + + + b105 + b105 + 9 + 1 + + + b106 + b106 + 10 + 1 + + + b107 + b107 + 11 + 1 + + + b108 + b108 + 12 + 1 + + + b109 + b109 + 13 + 1 + + + b110 + b110 + 14 + 1 + + + b111 + b111 + 15 + 1 + + + b112 + b112 + 16 + 1 + + + b113 + b113 + 17 + 1 + + + b114 + b114 + 18 + 1 + + + b115 + b115 + 19 + 1 + + + b116 + b116 + 20 + 1 + + + b117 + b117 + 21 + 1 + + + b118 + b118 + 22 + 1 + + + b119 + b119 + 23 + 1 + + + b120 + b120 + 24 + 1 + + + b121 + b121 + 25 + 1 + + + b122 + b122 + 26 + 1 + + + b123 + b123 + 27 + 1 + + + b124 + b124 + 28 + 1 + + + b125 + b125 + 29 + 1 + + + b126 + b126 + 30 + 1 + + + b127 + b127 + 31 + 1 + + + + + K2RR + K2RR + key registers + 0x34 + 0x20 + write-only + 0x00000000 + + + b64 + b64 + 0 + 1 + + + b65 + b65 + 1 + 1 + + + b66 + b66 + 2 + 1 + + + b67 + b67 + 3 + 1 + + + b68 + b68 + 4 + 1 + + + b69 + b69 + 5 + 1 + + + b70 + b70 + 6 + 1 + + + b71 + b71 + 7 + 1 + + + b72 + b72 + 8 + 1 + + + b73 + b73 + 9 + 1 + + + b74 + b74 + 10 + 1 + + + b75 + b75 + 11 + 1 + + + b76 + b76 + 12 + 1 + + + b77 + b77 + 13 + 1 + + + b78 + b78 + 14 + 1 + + + b79 + b79 + 15 + 1 + + + b80 + b80 + 16 + 1 + + + b81 + b81 + 17 + 1 + + + b82 + b82 + 18 + 1 + + + b83 + b83 + 19 + 1 + + + b84 + b84 + 20 + 1 + + + b85 + b85 + 21 + 1 + + + b86 + b86 + 22 + 1 + + + b87 + b87 + 23 + 1 + + + b88 + b88 + 24 + 1 + + + b89 + b89 + 25 + 1 + + + b90 + b90 + 26 + 1 + + + b91 + b91 + 27 + 1 + + + b92 + b92 + 28 + 1 + + + b93 + b93 + 29 + 1 + + + b94 + b94 + 30 + 1 + + + b95 + b95 + 31 + 1 + + + + + K3LR + K3LR + key registers + 0x38 + 0x20 + write-only + 0x00000000 + + + b32 + b32 + 0 + 1 + + + b33 + b33 + 1 + 1 + + + b34 + b34 + 2 + 1 + + + b35 + b35 + 3 + 1 + + + b36 + b36 + 4 + 1 + + + b37 + b37 + 5 + 1 + + + b38 + b38 + 6 + 1 + + + b39 + b39 + 7 + 1 + + + b40 + b40 + 8 + 1 + + + b41 + b41 + 9 + 1 + + + b42 + b42 + 10 + 1 + + + b43 + b43 + 11 + 1 + + + b44 + b44 + 12 + 1 + + + b45 + b45 + 13 + 1 + + + b46 + b46 + 14 + 1 + + + b47 + b47 + 15 + 1 + + + b48 + b48 + 16 + 1 + + + b49 + b49 + 17 + 1 + + + b50 + b50 + 18 + 1 + + + b51 + b51 + 19 + 1 + + + b52 + b52 + 20 + 1 + + + b53 + b53 + 21 + 1 + + + b54 + b54 + 22 + 1 + + + b55 + b55 + 23 + 1 + + + b56 + b56 + 24 + 1 + + + b57 + b57 + 25 + 1 + + + b58 + b58 + 26 + 1 + + + b59 + b59 + 27 + 1 + + + b60 + b60 + 28 + 1 + + + b61 + b61 + 29 + 1 + + + b62 + b62 + 30 + 1 + + + b63 + b63 + 31 + 1 + + + + + K3RR + K3RR + key registers + 0x3C + 0x20 + write-only + 0x00000000 + + + b0 + b0 + 0 + 1 + + + b1 + b1 + 1 + 1 + + + b2 + b2 + 2 + 1 + + + b3 + b3 + 3 + 1 + + + b4 + b4 + 4 + 1 + + + b5 + b5 + 5 + 1 + + + b6 + b6 + 6 + 1 + + + b7 + b7 + 7 + 1 + + + b8 + b8 + 8 + 1 + + + b9 + b9 + 9 + 1 + + + b10 + b10 + 10 + 1 + + + b11 + b11 + 11 + 1 + + + b12 + b12 + 12 + 1 + + + b13 + b13 + 13 + 1 + + + b14 + b14 + 14 + 1 + + + b15 + b15 + 15 + 1 + + + b16 + b16 + 16 + 1 + + + b17 + b17 + 17 + 1 + + + b18 + b18 + 18 + 1 + + + b19 + b19 + 19 + 1 + + + b20 + b20 + 20 + 1 + + + b21 + b21 + 21 + 1 + + + b22 + b22 + 22 + 1 + + + b23 + b23 + 23 + 1 + + + b24 + b24 + 24 + 1 + + + b25 + b25 + 25 + 1 + + + b26 + b26 + 26 + 1 + + + b27 + b27 + 27 + 1 + + + b28 + b28 + 28 + 1 + + + b29 + b29 + 29 + 1 + + + b30 + b30 + 30 + 1 + + + b31 + b31 + 31 + 1 + + + + + IV0LR + IV0LR + initialization vector + registers + 0x40 + 0x20 + read-write + 0x00000000 + + + IV31 + IV31 + 0 + 1 + + + IV30 + IV30 + 1 + 1 + + + IV29 + IV29 + 2 + 1 + + + IV28 + IV28 + 3 + 1 + + + IV27 + IV27 + 4 + 1 + + + IV26 + IV26 + 5 + 1 + + + IV25 + IV25 + 6 + 1 + + + IV24 + IV24 + 7 + 1 + + + IV23 + IV23 + 8 + 1 + + + IV22 + IV22 + 9 + 1 + + + IV21 + IV21 + 10 + 1 + + + IV20 + IV20 + 11 + 1 + + + IV19 + IV19 + 12 + 1 + + + IV18 + IV18 + 13 + 1 + + + IV17 + IV17 + 14 + 1 + + + IV16 + IV16 + 15 + 1 + + + IV15 + IV15 + 16 + 1 + + + IV14 + IV14 + 17 + 1 + + + IV13 + IV13 + 18 + 1 + + + IV12 + IV12 + 19 + 1 + + + IV11 + IV11 + 20 + 1 + + + IV10 + IV10 + 21 + 1 + + + IV9 + IV9 + 22 + 1 + + + IV8 + IV8 + 23 + 1 + + + IV7 + IV7 + 24 + 1 + + + IV6 + IV6 + 25 + 1 + + + IV5 + IV5 + 26 + 1 + + + IV4 + IV4 + 27 + 1 + + + IV3 + IV3 + 28 + 1 + + + IV2 + IV2 + 29 + 1 + + + IV1 + IV1 + 30 + 1 + + + IV0 + IV0 + 31 + 1 + + + + + IV0RR + IV0RR + initialization vector + registers + 0x44 + 0x20 + read-write + 0x00000000 + + + IV63 + IV63 + 0 + 1 + + + IV62 + IV62 + 1 + 1 + + + IV61 + IV61 + 2 + 1 + + + IV60 + IV60 + 3 + 1 + + + IV59 + IV59 + 4 + 1 + + + IV58 + IV58 + 5 + 1 + + + IV57 + IV57 + 6 + 1 + + + IV56 + IV56 + 7 + 1 + + + IV55 + IV55 + 8 + 1 + + + IV54 + IV54 + 9 + 1 + + + IV53 + IV53 + 10 + 1 + + + IV52 + IV52 + 11 + 1 + + + IV51 + IV51 + 12 + 1 + + + IV50 + IV50 + 13 + 1 + + + IV49 + IV49 + 14 + 1 + + + IV48 + IV48 + 15 + 1 + + + IV47 + IV47 + 16 + 1 + + + IV46 + IV46 + 17 + 1 + + + IV45 + IV45 + 18 + 1 + + + IV44 + IV44 + 19 + 1 + + + IV43 + IV43 + 20 + 1 + + + IV42 + IV42 + 21 + 1 + + + IV41 + IV41 + 22 + 1 + + + IV40 + IV40 + 23 + 1 + + + IV39 + IV39 + 24 + 1 + + + IV38 + IV38 + 25 + 1 + + + IV37 + IV37 + 26 + 1 + + + IV36 + IV36 + 27 + 1 + + + IV35 + IV35 + 28 + 1 + + + IV34 + IV34 + 29 + 1 + + + IV33 + IV33 + 30 + 1 + + + IV32 + IV32 + 31 + 1 + + + + + IV1LR + IV1LR + initialization vector + registers + 0x48 + 0x20 + read-write + 0x00000000 + + + IV95 + IV95 + 0 + 1 + + + IV94 + IV94 + 1 + 1 + + + IV93 + IV93 + 2 + 1 + + + IV92 + IV92 + 3 + 1 + + + IV91 + IV91 + 4 + 1 + + + IV90 + IV90 + 5 + 1 + + + IV89 + IV89 + 6 + 1 + + + IV88 + IV88 + 7 + 1 + + + IV87 + IV87 + 8 + 1 + + + IV86 + IV86 + 9 + 1 + + + IV85 + IV85 + 10 + 1 + + + IV84 + IV84 + 11 + 1 + + + IV83 + IV83 + 12 + 1 + + + IV82 + IV82 + 13 + 1 + + + IV81 + IV81 + 14 + 1 + + + IV80 + IV80 + 15 + 1 + + + IV79 + IV79 + 16 + 1 + + + IV78 + IV78 + 17 + 1 + + + IV77 + IV77 + 18 + 1 + + + IV76 + IV76 + 19 + 1 + + + IV75 + IV75 + 20 + 1 + + + IV74 + IV74 + 21 + 1 + + + IV73 + IV73 + 22 + 1 + + + IV72 + IV72 + 23 + 1 + + + IV71 + IV71 + 24 + 1 + + + IV70 + IV70 + 25 + 1 + + + IV69 + IV69 + 26 + 1 + + + IV68 + IV68 + 27 + 1 + + + IV67 + IV67 + 28 + 1 + + + IV66 + IV66 + 29 + 1 + + + IV65 + IV65 + 30 + 1 + + + IV64 + IV64 + 31 + 1 + + + + + IV1RR + IV1RR + initialization vector + registers + 0x4C + 0x20 + read-write + 0x00000000 + + + IV127 + IV127 + 0 + 1 + + + IV126 + IV126 + 1 + 1 + + + IV125 + IV125 + 2 + 1 + + + IV124 + IV124 + 3 + 1 + + + IV123 + IV123 + 4 + 1 + + + IV122 + IV122 + 5 + 1 + + + IV121 + IV121 + 6 + 1 + + + IV120 + IV120 + 7 + 1 + + + IV119 + IV119 + 8 + 1 + + + IV118 + IV118 + 9 + 1 + + + IV117 + IV117 + 10 + 1 + + + IV116 + IV116 + 11 + 1 + + + IV115 + IV115 + 12 + 1 + + + IV114 + IV114 + 13 + 1 + + + IV113 + IV113 + 14 + 1 + + + IV112 + IV112 + 15 + 1 + + + IV111 + IV111 + 16 + 1 + + + IV110 + IV110 + 17 + 1 + + + IV109 + IV109 + 18 + 1 + + + IV108 + IV108 + 19 + 1 + + + IV107 + IV107 + 20 + 1 + + + IV106 + IV106 + 21 + 1 + + + IV105 + IV105 + 22 + 1 + + + IV104 + IV104 + 23 + 1 + + + IV103 + IV103 + 24 + 1 + + + IV102 + IV102 + 25 + 1 + + + IV101 + IV101 + 26 + 1 + + + IV100 + IV100 + 27 + 1 + + + IV99 + IV99 + 28 + 1 + + + IV98 + IV98 + 29 + 1 + + + IV97 + IV97 + 30 + 1 + + + IV96 + IV96 + 31 + 1 + + + + + CSGCMCCM0R + CSGCMCCM0R + context swap register + 0x50 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM0R + CSGCMCCM0R + 0 + 32 + + + + + CSGCMCCM1R + CSGCMCCM1R + context swap register + 0x54 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM1R + CSGCMCCM1R + 0 + 32 + + + + + CSGCMCCM2R + CSGCMCCM2R + context swap register + 0x58 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM2R + CSGCMCCM2R + 0 + 32 + + + + + CSGCMCCM3R + CSGCMCCM3R + context swap register + 0x5C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM3R + CSGCMCCM3R + 0 + 32 + + + + + CSGCMCCM4R + CSGCMCCM4R + context swap register + 0x60 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM4R + CSGCMCCM4R + 0 + 32 + + + + + CSGCMCCM5R + CSGCMCCM5R + context swap register + 0x64 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM5R + CSGCMCCM5R + 0 + 32 + + + + + CSGCMCCM6R + CSGCMCCM6R + context swap register + 0x68 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM6R + CSGCMCCM6R + 0 + 32 + + + + + CSGCMCCM7R + CSGCMCCM7R + context swap register + 0x6C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM7R + CSGCMCCM7R + 0 + 32 + + + + + CSGCM0R + CSGCM0R + context swap register + 0x70 + 0x20 + read-write + 0x00000000 + + + CSGCM0R + CSGCM0R + 0 + 32 + + + + + CSGCM1R + CSGCM1R + context swap register + 0x74 + 0x20 + read-write + 0x00000000 + + + CSGCM1R + CSGCM1R + 0 + 32 + + + + + CSGCM2R + CSGCM2R + context swap register + 0x78 + 0x20 + read-write + 0x00000000 + + + CSGCM2R + CSGCM2R + 0 + 32 + + + + + CSGCM3R + CSGCM3R + context swap register + 0x7C + 0x20 + read-write + 0x00000000 + + + CSGCM3R + CSGCM3R + 0 + 32 + + + + + CSGCM4R + CSGCM4R + context swap register + 0x80 + 0x20 + read-write + 0x00000000 + + + CSGCM4R + CSGCM4R + 0 + 32 + + + + + CSGCM5R + CSGCM5R + context swap register + 0x84 + 0x20 + read-write + 0x00000000 + + + CSGCM5R + CSGCM5R + 0 + 32 + + + + + CSGCM6R + CSGCM6R + context swap register + 0x88 + 0x20 + read-write + 0x00000000 + + + CSGCM6R + CSGCM6R + 0 + 32 + + + + + CSGCM7R + CSGCM7R + context swap register + 0x8C + 0x20 + read-write + 0x00000000 + + + CSGCM7R + CSGCM7R + 0 + 32 + + + + + + + DCMI + Digital camera interface + DCMI + 0x50050000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ENABLE + DCMI enable + 14 + 1 + + + EDM + Extended data mode + 10 + 2 + + + FCRC + Frame capture rate control + 8 + 2 + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + + + PCKPOL + Pixel clock polarity + 5 + 1 + + + ESS + Embedded synchronization + select + 4 + 1 + + + JPEG + JPEG format + 3 + 1 + + + CROP + Crop feature + 2 + 1 + + + CM + Capture mode + 1 + 1 + + + CAPTURE + Capture enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + FMC + Flexible memory controller + FSMC + 0xA0000000 + + 0x0 + 0x1000 + registers + + + FMC + FMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR + PCR + PC Card/NAND Flash control + register + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR + SR + FIFO status and interrupt + register + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM + PMEM + Common memory space timing + register + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT + PATT + Attribute memory space timing + register + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR + ECCR + ECC result register + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + SDCR1 + SDCR1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDCR2 + SDCR2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDTR1 + SDTR1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDTR2 + SDTR2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDCMR + SDCMR + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + MODE + Command mode + 0 + 3 + write-only + + + CTB2 + Command target bank 2 + 3 + 1 + write-only + + + CTB1 + Command target bank 1 + 4 + 1 + write-only + + + NRFS + Number of Auto-refresh + 5 + 4 + read-write + + + MRD + Mode Register definition + 9 + 13 + read-write + + + + + SDRTR + SDRTR + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag + 0 + 1 + write-only + + + COUNT + Refresh Timer Count + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + RE + Refresh error flag + 0 + 1 + + + MODES1 + Status Mode for Bank 1 + 1 + 2 + + + MODES2 + Status Mode for Bank 2 + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 4 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLSAIRDYC + PLLSAI Ready Interrupt + Clear + 22 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLSAIRDYIE + PLLSAI Ready Interrupt + Enable + 14 + 1 + read-write + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLSAIRDYF + PLLSAI ready interrupt + flag + 6 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + ETHMACRST + Ethernet MAC reset + 25 + 1 + + + DMA2DRST + DMA2D reset + 23 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOKRST + IO port K reset + 10 + 1 + + + GPIOJRST + IO port J reset + 9 + 1 + + + GPIOIRST + IO port I reset + 8 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + RNGRST + Random number generator module + reset + 6 + 1 + + + HSAHRST + Hash module reset + 5 + 1 + + + CRYPRST + Cryptographic module reset + 4 + 1 + + + DCMIRST + Camera interface reset + 0 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FMCRST + Flexible memory controller module + reset + 0 + 1 + + + QSPIRST + Quad SPI memory controller + reset + 1 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM2 reset + 0 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + SPDIFRXRST + SPDIF-RX reset + 16 + 1 + + + CECRST + HDMI-CEC reset + 27 + 1 + + + LPTIM1RST + Low power timer 1 reset + 9 + 1 + + + I2C4RST + I2C 4 reset + 24 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 reset + 0 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM11RST + TIM11 reset + 18 + 1 + + + SPI5RST + SPI5 reset + 20 + 1 + + + SPI6RST + SPI6 reset + 21 + 1 + + + SAI1RST + SAI1 reset + 22 + 1 + + + LTDCRST + LTDC reset + 26 + 1 + + + SAI2RST + SAI2 reset + 23 + 1 + + + SDMMC1RST + SDMMC1 reset + 11 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + ETHMACPTPEN + Ethernet PTP clock enable + 28 + 1 + + + ETHMACRXEN + Ethernet Reception clock + enable + 27 + 1 + + + ETHMACTXEN + Ethernet Transmission clock + enable + 26 + 1 + + + ETHMACEN + Ethernet MAC clock enable + 25 + 1 + + + DMA2DEN + DMA2D clock enable + 23 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + CCMDATARAMEN + CCM data RAM clock enable + 20 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOKEN + IO port K clock enable + 10 + 1 + + + GPIOJEN + IO port J clock enable + 9 + 1 + + + GPIOIEN + IO port I clock enable + 8 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + RNGEN + Random number generator clock + enable + 6 + 1 + + + HASHEN + Hash modules clock enable + 5 + 1 + + + CRYPEN + Cryptographic modules clock + enable + 4 + 1 + + + DCMIEN + Camera interface enable + 0 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FMCEN + Flexible memory controller module clock + enable + 0 + 1 + + + QSPIEN + Quad SPI memory controller clock + enable + 1 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + CAN2EN + CAN 2 clock enable + 26 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + UART7ENR + UART7 clock enable + 30 + 1 + + + UART8ENR + UART8 clock enable + 31 + 1 + + + SPDIFRXEN + SPDIF-RX clock enable + 16 + 1 + + + CECEN + HDMI-CEN clock enable + 27 + 1 + + + LPTMI1EN + Low power timer 1 clock + enable + 9 + 1 + + + I2C4EN + I2C4 clock enable + 24 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4ENR + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + SPI5ENR + SPI5 clock enable + 20 + 1 + + + SPI6ENR + SPI6 clock enable + 21 + 1 + + + SAI1EN + SAI1 clock enable + 22 + 1 + + + LTDCEN + LTDC clock enable + 26 + 1 + + + SAI2EN + SAI2 clock enable + 23 + 1 + + + SDMMC1EN + SDMMC1 clock enable + 11 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOILPEN + IO port I clock enable during Sleep + mode + 8 + 1 + + + GPIOJLPEN + IO port J clock enable during Sleep + mode + 9 + 1 + + + GPIOKLPEN + IO port K clock enable during Sleep + mode + 10 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + SRAM3LPEN + SRAM 3 interface clock enable during + Sleep mode + 19 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + DMA2DLPEN + DMA2D clock enable during Sleep + mode + 23 + 1 + + + ETHMACLPEN + Ethernet MAC clock enable during Sleep + mode + 25 + 1 + + + ETHMACTXLPEN + Ethernet transmission clock enable + during Sleep mode + 26 + 1 + + + ETHMACRXLPEN + Ethernet reception clock enable during + Sleep mode + 27 + 1 + + + ETHMACPTPLPEN + Ethernet PTP clock enable during Sleep + mode + 28 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + RNGLPEN + Random number generator clock enable + during Sleep mode + 6 + 1 + + + HASHLPEN + Hash modules clock enable during Sleep + mode + 5 + 1 + + + CRYPLPEN + Cryptography modules clock enable during + Sleep mode + 4 + 1 + + + DCMILPEN + Camera interface enable during Sleep + mode + 0 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FMCLPEN + Flexible memory controller module clock + enable during Sleep mode + 0 + 1 + + + QSPILPEN + Quand SPI memory controller clock enable + during Sleep mode + 1 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during Sleep + mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during Sleep + mode + 31 + 1 + + + SPDIFRXLPEN + SPDIF-RX clock enable during sleep + mode + 16 + 1 + + + CECLPEN + HDMI-CEN clock enable during Sleep + mode + 27 + 1 + + + LPTIM1LPEN + low power timer 1 clock enable during + Sleep mode + 9 + 1 + + + I2C4LPEN + I2C4 clock enable during Sleep + mode + 24 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI 4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + SPI5LPEN + SPI 5 clock enable during Sleep + mode + 20 + 1 + + + SPI6LPEN + SPI 6 clock enable during Sleep + mode + 21 + 1 + + + SAI1LPEN + SAI1 clock enable during sleep + mode + 22 + 1 + + + LTDCLPEN + LTDC clock enable during sleep + mode + 26 + 1 + + + SAI2LPEN + SAI2 clock enable during sleep + mode + 23 + 1 + + + SDMMC1LPEN + SDMMC1 clock enable during Sleep + mode + 11 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SR + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SQ + PLLI2S division factor for SAI1 + clock + 24 + 4 + + + PLLI2SN + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + PLLSAICFGR + PLLSAICFGR + PLL configuration register + 0x88 + 0x20 + read-write + 0x20003000 + + + PLLSAIN + PLLSAI division factor for + VCO + 6 + 9 + + + PLLSAIP + PLLSAI division factor for 48MHz + clock + 16 + 2 + + + PLLSAIQ + PLLSAI division factor for SAI + clock + 24 + 4 + + + PLLSAIR + PLLSAI division factor for LCD + clock + 28 + 3 + + + + + DKCFGR1 + DKCFGR1 + dedicated clocks configuration + register + 0x8C + 0x20 + read-write + 0x20003000 + + + PLLI2SDIV + PLLI2S division factor for SAI1 + clock + 0 + 5 + + + PLLSAIDIVQ + PLLSAI division factor for SAI1 + clock + 8 + 5 + + + PLLSAIDIVR + division factor for + LCD_CLK + 16 + 2 + + + SAI1SEL + SAI1 clock source + selection + 20 + 2 + + + SAI2SEL + SAI2 clock source + selection + 22 + 2 + + + TIMPRE + Timers clocks prescalers + selection + 24 + 1 + + + + + DKCFGR2 + DKCFGR2 + dedicated clocks configuration + register + 0x90 + 0x20 + read-write + 0x20003000 + + + USART1SEL + USART 1 clock source + selection + 0 + 2 + + + USART2SEL + USART 2 clock source + selection + 2 + 2 + + + USART3SEL + USART 3 clock source + selection + 4 + 2 + + + UART4SEL + UART 4 clock source + selection + 6 + 2 + + + UART5SEL + UART 5 clock source + selection + 8 + 2 + + + USART6SEL + USART 6 clock source + selection + 10 + 2 + + + UART7SEL + UART 7 clock source + selection + 12 + 2 + + + UART8SEL + UART 8 clock source + selection + 14 + 2 + + + I2C1SEL + I2C1 clock source + selection + 16 + 2 + + + I2C2SEL + I2C2 clock source + selection + 18 + 2 + + + I2C3SEL + I2C3 clock source + selection + 20 + 2 + + + I2C4SEL + I2C4 clock source + selection + 22 + 2 + + + LPTIM1SEL + Low power timer 1 clock source + selection + 24 + 2 + + + CECSEL + HDMI-CEC clock source + selection + 26 + 1 + + + CK48MSEL + 48MHz clock source + selection + 27 + 1 + + + SDMMCSEL + SDMMC clock source + selection + 28 + 1 + + + + + + + GPIOD + General-purpose I/Os + GPIO + 0X40020C00 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function + lowregister + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port D Reset bit 0 + 0 + 1 + + + BR1 + Port D Reset bit 1 + 1 + 1 + + + BR2 + Port D Reset bit 2 + 2 + 1 + + + BR3 + Port D Reset bit 3 + 3 + 1 + + + BR4 + Port D Reset bit 4 + 4 + 1 + + + BR5 + Port D Reset bit 5 + 5 + 1 + + + BR6 + Port D Reset bit 6 + 6 + 1 + + + BR7 + Port D Reset bit 7 + 7 + 1 + + + BR8 + Port D Reset bit 8 + 8 + 1 + + + BR9 + Port D Reset bit 9 + 9 + 1 + + + BR10 + Port D Reset bit 10 + 10 + 1 + + + BR11 + Port D Reset bit 11 + 11 + 1 + + + BR12 + Port D Reset bit 12 + 12 + 1 + + + BR13 + Port D Reset bit 13 + 13 + 1 + + + BR14 + Port D Reset bit 14 + 14 + 1 + + + BR15 + Port D Reset bit 15 + 15 + 1 + + + + + + + GPIOC + 0x40020800 + + + GPIOK + 0X40022800 + + + GPIOJ + 0X40022400 + + + GPIOI + 0X40022000 + + + GPIOH + 0X40021C00 + + + GPIOG + 0X40021800 + + + GPIOF + 0X40021400 + + + GPIOE + 0X40021000 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port B Reset bit 0 + 0 + 1 + + + BR1 + Port B Reset bit 1 + 1 + 1 + + + BR2 + Port B Reset bit 2 + 2 + 1 + + + BR3 + Port B Reset bit 3 + 3 + 1 + + + BR4 + Port B Reset bit 4 + 4 + 1 + + + BR5 + Port B Reset bit 5 + 5 + 1 + + + BR6 + Port B Reset bit 6 + 6 + 1 + + + BR7 + Port B Reset bit 7 + 7 + 1 + + + BR8 + Port B Reset bit 8 + 8 + 1 + + + BR9 + Port B Reset bit 9 + 9 + 1 + + + BR10 + Port B Reset bit 10 + 10 + 1 + + + BR11 + Port B Reset bit 11 + 11 + 1 + + + BR12 + Port B Reset bit 12 + 12 + 1 + + + BR13 + Port B Reset bit 13 + 13 + 1 + + + BR14 + Port B Reset bit 14 + 14 + 1 + + + BR15 + Port B Reset bit 15 + 15 + 1 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port A Reset bit 0 + 0 + 1 + + + BR1 + Port A Reset bit 1 + 1 + 1 + + + BR2 + Port A Reset bit 2 + 2 + 1 + + + BR3 + Port A Reset bit 3 + 3 + 1 + + + BR4 + Port A Reset bit 4 + 4 + 1 + + + BR5 + Port A Reset bit 5 + 5 + 1 + + + BR6 + Port A Reset bit 6 + 6 + 1 + + + BR7 + Port A Reset bit 7 + 7 + 1 + + + BR8 + Port A Reset bit 8 + 8 + 1 + + + BR9 + Port A Reset bit 9 + 9 + 1 + + + BR10 + Port A Reset bit 10 + 10 + 1 + + + BR11 + Port A Reset bit 11 + 11 + 1 + + + BR12 + Port A Reset bit 12 + 12 + 1 + + + BR13 + Port A Reset bit 13 + 13 + 1 + + + BR14 + Port A Reset bit 14 + 14 + 1 + + + BR15 + Port A Reset bit 15 + 15 + 1 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + Memory mapping selection + 0 + 3 + + + FB_MODE + Flash bank mode selection + 8 + 1 + + + SWP_FMC + FMC memory mapping swap + 10 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + Ethernet PHY interface + selection + 23 + 1 + + + ADC1DC2 + ADC1DC2 + 16 + 1 + + + ADC2DC2 + ADC2DC2 + 17 + 1 + + + ADC3DC2 + ADC3DC2 + 18 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + FRE + Frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI4 + 0x40013400 + + SPI4 + SPI 4 global interrupt + 84 + + + + SPI5 + 0x40015000 + + SPI5 + SPI 5 global interrupt + 85 + + + + SPI3 + Serial peripheral interface + SPI + 0x40003C00 + + 0x0 + 0x400 + registers + + + SPI3 + SPI3 global interrupt + 51 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + _FRE + Frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI6 + Serial peripheral interface + SPI + 0x40015400 + + 0x0 + 0x400 + registers + + + SPI6 + SPI 6 global interrupt + 86 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + BSY + Busy flag + 7 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + MODF + Mode fault + 5 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FRE + Frame format error + 8 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + UDR + Underrun flag + 3 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x100 + registers + + + ADC + ADC1 global interrupt + 18 + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC2 + 0x40012100 + + + ADC3 + 0x40012200 + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + power control register + 0x0 + 0x20 + read-write + 0x0000C000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + LPUDS + Low-power regulator in deepsleep + under-drive mode + 10 + 1 + + + MRUDS + Main regulator in deepsleep under-drive + mode + 11 + 1 + + + ADCDC1 + ADCDC1 + 13 + 1 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ODEN + Over-drive enable + 16 + 1 + + + ODSWEN + Over-drive switching + enabled + 17 + 1 + + + UDEN + Under-drive enable in stop + mode + 18 + 2 + + + + + CSR1 + CSR1 + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUIF + Wakeup internal flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + ODRDY + Over-drive mode ready + 16 + 1 + read-write + + + ODSWRDY + Over-drive mode switching + ready + 17 + 1 + read-write + + + UDRDY + Under-drive ready flag + 18 + 2 + read-write + + + + + CR2 + CR2 + power control register + 0x8 + 0x20 + 0x00000000 + + + CWUPF1 + Clear Wakeup Pin flag for + PA0 + 0 + 1 + read-only + + + CWUPF2 + Clear Wakeup Pin flag for + PA2 + 1 + 1 + read-only + + + CWUPF3 + Clear Wakeup Pin flag for + PC1 + 2 + 1 + read-only + + + CWUPF4 + Clear Wakeup Pin flag for + PC13 + 3 + 1 + read-only + + + CWUPF5 + Clear Wakeup Pin flag for + PI8 + 4 + 1 + read-only + + + CWUPF6 + Clear Wakeup Pin flag for + PI11 + 5 + 1 + read-only + + + WUPP1 + Wakeup pin polarity bit for + PA0 + 8 + 1 + read-write + + + WUPP2 + Wakeup pin polarity bit for + PA2 + 9 + 1 + read-write + + + WUPP3 + Wakeup pin polarity bit for + PC1 + 10 + 1 + read-write + + + WUPP4 + Wakeup pin polarity bit for + PC13 + 11 + 1 + read-write + + + WUPP5 + Wakeup pin polarity bit for + PI8 + 12 + 1 + read-write + + + WUPP6 + Wakeup pin polarity bit for + PI11 + 13 + 1 + read-write + + + + + CSR2 + CSR2 + power control/status register + 0xC + 0x20 + 0x00000000 + + + WUPF1 + Wakeup Pin flag for PA0 + 0 + 1 + read-only + + + WUPF2 + Wakeup Pin flag for PA2 + 1 + 1 + read-only + + + WUPF3 + Wakeup Pin flag for PC1 + 2 + 1 + read-only + + + WUPF4 + Wakeup Pin flag for PC13 + 3 + 1 + read-only + + + WUPF5 + Wakeup Pin flag for PI8 + 4 + 1 + read-only + + + WUPF6 + Wakeup Pin flag for PI11 + 5 + 1 + read-only + + + EWUP1 + Enable Wakeup pin for PA0 + 8 + 1 + read-write + + + EWUP2 + Enable Wakeup pin for PA2 + 9 + 1 + read-write + + + EWUP3 + Enable Wakeup pin for PC1 + 10 + 1 + read-write + + + EWUP4 + Enable Wakeup pin for PC13 + 11 + 1 + read-write + + + EWUP5 + Enable Wakeup pin for PI8 + 12 + 1 + read-write + + + EWUP6 + Enable Wakeup pin for PI11 + 13 + 1 + read-write + + + + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + WINR + WINR + Window register + 0x10 + 0x20 + read-write + 0x00000000 + + + WIN + Watchdog counter window + value + 0 + 12 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0x400 + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection - + bit[2:0] + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x0000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M3 + Output Compare 5 mode + 16 + 1 + + + OC6M3 + Output Compare 6 mode + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x0000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CRR6 + CRR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x0000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + + + TIM8 + 0x40010400 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR1 + OR1 + TIM2 option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + TI4_RMP + Input Capture 4 remap + 2 + 2 + + + ETR1_RMP + External trigger remap + 1 + 1 + + + ITR1_RMP + Internal trigger 1 remap + 0 + 1 + + + + + OR2 + OR2 + TIM2 option register 2 + 0x60 + 0x20 + read-write + 0x0000 + + + ETRSEL + ETR source selection + 14 + 3 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR1 + OR1 + TIM3 option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + TI1_RMP + Input Capture 1 remap + 0 + 2 + + + + + OR2 + OR2 + TIM3 option register 2 + 0x60 + 0x20 + read-write + 0x0000 + + + ETRSEL + ETR source selection + 14 + 3 + + + + + + + TIM4 + General purpose timers + TIM + 0x40000800 + + 0x0 + 0x400 + registers + + + TIM4 + TIM4 global interrupt + 30 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM5 + 0x40000C00 + + TIM5 + TIM5 global interrupt + 50 + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x00000000 + + + SMS3 + Slave mode selection + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + TI1_RMP + TIM11 Input 1 remapping + capability + 0 + 2 + + + + + + + TIM11 + 0x40014800 + + + TIM13 + 0x40001C00 + + + TIM14 + 0x40002000 + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + Ethernet_MAC + Ethernet: media access control + (MAC) + Ethernet + 0x40028000 + + 0x0 + 0x100 + registers + + + + MACCR + MACCR + Ethernet MAC configuration + register + 0x0 + 0x20 + read-write + 0x0008000 + + + RE + RE + 2 + 1 + + + TE + TE + 3 + 1 + + + DC + DC + 4 + 1 + + + BL + BL + 5 + 2 + + + APCS + APCS + 7 + 1 + + + RD + RD + 9 + 1 + + + IPCO + IPCO + 10 + 1 + + + DM + DM + 11 + 1 + + + LM + LM + 12 + 1 + + + ROD + ROD + 13 + 1 + + + FES + FES + 14 + 1 + + + CSD + CSD + 16 + 1 + + + IFG + IFG + 17 + 3 + + + JD + JD + 22 + 1 + + + WD + WD + 23 + 1 + + + CSTF + CSTF + 25 + 1 + + + + + MACFFR + MACFFR + Ethernet MAC frame filter + register + 0x4 + 0x20 + read-write + 0x00000000 + + + PM + PM + 0 + 1 + + + HU + HU + 1 + 1 + + + HM + HM + 2 + 1 + + + DAIF + DAIF + 3 + 1 + + + RAM + RAM + 4 + 1 + + + BFD + BFD + 5 + 1 + + + PCF + PCF + 6 + 1 + + + SAIF + SAIF + 7 + 1 + + + SAF + SAF + 8 + 1 + + + HPF + HPF + 9 + 1 + + + RA + RA + 31 + 1 + + + + + MACHTHR + MACHTHR + Ethernet MAC hash table high + register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + HTH + 0 + 32 + + + + + MACHTLR + MACHTLR + Ethernet MAC hash table low + register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + HTL + 0 + 32 + + + + + MACMIIAR + MACMIIAR + Ethernet MAC MII address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MB + 0 + 1 + + + MW + MW + 1 + 1 + + + CR + CR + 2 + 3 + + + MR + MR + 6 + 5 + + + PA + PA + 11 + 5 + + + + + MACMIIDR + MACMIIDR + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + TD + TD + 0 + 16 + + + + + MACFCR + MACFCR + Ethernet MAC flow control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB + FCB + 0 + 1 + + + TFCE + TFCE + 1 + 1 + + + RFCE + RFCE + 2 + 1 + + + UPFD + UPFD + 3 + 1 + + + PLT + PLT + 4 + 2 + + + ZQPD + ZQPD + 7 + 1 + + + PT + PT + 16 + 16 + + + + + MACVLANTR + MACVLANTR + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VLANTI + VLANTI + 0 + 16 + + + VLANTC + VLANTC + 16 + 1 + + + + + MACPMTCSR + MACPMTCSR + Ethernet MAC PMT control and status + register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + PD + 0 + 1 + + + MPE + MPE + 1 + 1 + + + WFE + WFE + 2 + 1 + + + MPR + MPR + 5 + 1 + + + WFR + WFR + 6 + 1 + + + GU + GU + 9 + 1 + + + WFFRPR + WFFRPR + 31 + 1 + + + + + MACDBGR + MACDBGR + Ethernet MAC debug register + 0x34 + 0x20 + read-only + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MACSR + MACSR + Ethernet MAC interrupt status + register + 0x38 + 0x20 + 0x00000000 + + + PMTS + PMTS + 3 + 1 + read-only + + + MMCS + MMCS + 4 + 1 + read-only + + + MMCRS + MMCRS + 5 + 1 + read-only + + + MMCTS + MMCTS + 6 + 1 + read-only + + + TSTS + TSTS + 9 + 1 + read-write + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask + register + 0x3C + 0x20 + read-write + 0x00000000 + + + PMTIM + PMTIM + 3 + 1 + + + TSTIM + TSTIM + 9 + 1 + + + + + MACA0HR + MACA0HR + Ethernet MAC address 0 high + register + 0x40 + 0x20 + 0x0010FFFF + + + MACA0H + MAC address0 high + 0 + 16 + read-write + + + MO + Always 1 + 31 + 1 + read-only + + + + + MACA0LR + MACA0LR + Ethernet MAC address 0 low + register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MACA0L + 0 + 0 + 32 + + + + + MACA1HR + MACA1HR + Ethernet MAC address 1 high + register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MACA1H + MACA1H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA1LR + MACA1LR + Ethernet MAC address1 low + register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MACA1LR + MACA1LR + 0 + 32 + + + + + MACA2HR + MACA2HR + Ethernet MAC address 2 high + register + 0x50 + 0x20 + read-write + 0x0000FFFF + + + MAC2AH + MAC2AH + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA2LR + MACA2LR + Ethernet MAC address 2 low + register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MACA2L + MACA2L + 0 + 31 + + + + + MACA3HR + MACA3HR + Ethernet MAC address 3 high + register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MACA3H + MACA3H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3LR + MACA3LR + Ethernet MAC address 3 low + register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MBCA3L + MBCA3L + 0 + 32 + + + + + MACRWUFFER + MACRWUFFER + Ethernet MAC remote wakeup frame filter + register + 0x60 + 0x20 + read-write + 0xFFFFFFFF + + + + + Ethernet_MMC + Ethernet: MAC management counters + Ethernet + 0x40028100 + + 0x0 + 0x400 + registers + + + + MMCCR + MMCCR + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MMCRIR + MMCRIR + Ethernet MMC receive interrupt + register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCES + RFCES + 5 + 1 + + + RFAES + RFAES + 6 + 1 + + + RGUFS + RGUFS + 17 + 1 + + + + + MMCTIR + MMCTIR + Ethernet MMC transmit interrupt + register + 0x8 + 0x20 + read-only + 0x00000000 + + + TGFSCS + TGFSCS + 14 + 1 + + + TGFMSCS + TGFMSCS + 15 + 1 + + + TGFS + TGFS + 21 + 1 + + + + + MMCRIMR + MMCRIMR + Ethernet MMC receive interrupt mask + register + 0xC + 0x20 + read-write + 0x00000000 + + + RFCEM + RFCEM + 5 + 1 + + + RFAEM + RFAEM + 6 + 1 + + + RGUFM + RGUFM + 17 + 1 + + + + + MMCTIMR + MMCTIMR + Ethernet MMC transmit interrupt mask + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TGFSCM + TGFSCM + 14 + 1 + + + TGFMSCM + TGFMSCM + 15 + 1 + + + TGFM + TGFM + 16 + 1 + + + + + MMCTGFSCCR + MMCTGFSCCR + Ethernet MMC transmitted good frames after a + single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + TGFSCC + 0 + 32 + + + + + MMCTGFMSCCR + MMCTGFMSCCR + Ethernet MMC transmitted good frames after + more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + TGFMSCC + 0 + 32 + + + + + MMCTGFCR + MMCTGFCR + Ethernet MMC transmitted good frames counter + register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + HTL + 0 + 32 + + + + + MMCRFCECR + MMCRFCECR + Ethernet MMC received frames with CRC error + counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCFC + RFCFC + 0 + 32 + + + + + MMCRFAECR + MMCRFAECR + Ethernet MMC received frames with alignment + error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + RFAEC + 0 + 32 + + + + + MMCRGUFCR + MMCRGUFCR + MMC received good unicast frames counter + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + RGUFC + 0 + 32 + + + + + + + Ethernet_PTP + Ethernet: Precision time protocol + Ethernet + 0x40028700 + + 0x0 + 0x400 + registers + + + + PTPTSCR + PTPTSCR + Ethernet PTP time stamp control + register + 0x0 + 0x20 + read-write + 0x00002000 + + + TSE + TSE + 0 + 1 + + + TSFCU + TSFCU + 1 + 1 + + + TSPTPPSV2E + TSPTPPSV2E + 10 + 1 + + + TSSPTPOEFE + TSSPTPOEFE + 11 + 1 + + + TSSIPV6FE + TSSIPV6FE + 12 + 1 + + + TSSIPV4FE + TSSIPV4FE + 13 + 1 + + + TSSEME + TSSEME + 14 + 1 + + + TSSMRME + TSSMRME + 15 + 1 + + + TSCNT + TSCNT + 16 + 2 + + + TSPFFMAE + TSPFFMAE + 18 + 1 + + + TSSTI + TSSTI + 2 + 1 + + + TSSTU + TSSTU + 3 + 1 + + + TSITE + TSITE + 4 + 1 + + + TTSARU + TTSARU + 5 + 1 + + + TSSARFE + TSSARFE + 8 + 1 + + + TSSSR + TSSSR + 9 + 1 + + + + + PTPSSIR + PTPSSIR + Ethernet PTP subsecond increment + register + 0x4 + 0x20 + read-write + 0x00000000 + + + STSSI + STSSI + 0 + 8 + + + + + PTPTSHR + PTPTSHR + Ethernet PTP time stamp high + register + 0x8 + 0x20 + read-only + 0x00000000 + + + STS + STS + 0 + 32 + + + + + PTPTSLR + PTPTSLR + Ethernet PTP time stamp low + register + 0xC + 0x20 + read-only + 0x00000000 + + + STSS + STSS + 0 + 31 + + + STPNS + STPNS + 31 + 1 + + + + + PTPTSHUR + PTPTSHUR + Ethernet PTP time stamp high update + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSUS + TSUS + 0 + 32 + + + + + PTPTSLUR + PTPTSLUR + Ethernet PTP time stamp low update + register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSUSS + TSUSS + 0 + 31 + + + TSUPNS + TSUPNS + 31 + 1 + + + + + PTPTSAR + PTPTSAR + Ethernet PTP time stamp addend + register + 0x18 + 0x20 + read-write + 0x00000000 + + + TSA + TSA + 0 + 32 + + + + + PTPTTHR + PTPTTHR + Ethernet PTP target time high + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSH + 0 + 0 + 32 + + + + + PTPTTLR + PTPTTLR + Ethernet PTP target time low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTSL + TTSL + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status + register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSSO + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control + register + 0x2C + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + + + Ethernet_DMA + Ethernet: DMA controller operation + Ethernet + 0x40029000 + + 0x0 + 0x400 + registers + + + ETH + Ethernet global interrupt + 61 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + + DMABMR + DMABMR + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x00002101 + + + SR + SR + 0 + 1 + + + DA + DA + 1 + 1 + + + DSL + DSL + 2 + 5 + + + EDFE + EDFE + 7 + 1 + + + PBL + PBL + 8 + 6 + + + RTPR + RTPR + 14 + 2 + + + FB + FB + 16 + 1 + + + RDP + RDP + 17 + 6 + + + USP + USP + 23 + 1 + + + FPM + FPM + 24 + 1 + + + AAB + AAB + 25 + 1 + + + MB + MB + 26 + 1 + + + + + DMATPDR + DMATPDR + Ethernet DMA transmit poll demand + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + TPD + 0 + 32 + + + + + DMARPDR + DMARPDR + EHERNET DMA receive poll demand + register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + RPD + 0 + 32 + + + + + DMARDLAR + DMARDLAR + Ethernet DMA receive descriptor list address + register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + SRL + 0 + 32 + + + + + DMATDLAR + DMATDLAR + Ethernet DMA transmit descriptor list + address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + STL + 0 + 32 + + + + + DMASR + DMASR + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TS + TS + 0 + 1 + read-write + + + TPSS + TPSS + 1 + 1 + read-write + + + TBUS + TBUS + 2 + 1 + read-write + + + TJTS + TJTS + 3 + 1 + read-write + + + ROS + ROS + 4 + 1 + read-write + + + TUS + TUS + 5 + 1 + read-write + + + RS + RS + 6 + 1 + read-write + + + RBUS + RBUS + 7 + 1 + read-write + + + RPSS + RPSS + 8 + 1 + read-write + + + PWTS + PWTS + 9 + 1 + read-write + + + ETS + ETS + 10 + 1 + read-write + + + FBES + FBES + 13 + 1 + read-write + + + ERS + ERS + 14 + 1 + read-write + + + AIS + AIS + 15 + 1 + read-write + + + NIS + NIS + 16 + 1 + read-write + + + RPS + RPS + 17 + 3 + read-only + + + TPS + TPS + 20 + 3 + read-only + + + EBS + EBS + 23 + 3 + read-only + + + MMCS + MMCS + 27 + 1 + read-only + + + PMTS + PMTS + 28 + 1 + read-only + + + TSTS + TSTS + 29 + 1 + read-only + + + + + DMAOMR + DMAOMR + Ethernet DMA operation mode + register + 0x18 + 0x20 + read-write + 0x00000000 + + + SR + SR + 1 + 1 + + + OSF + OSF + 2 + 1 + + + RTC + RTC + 3 + 2 + + + FUGF + FUGF + 6 + 1 + + + FEF + FEF + 7 + 1 + + + ST + ST + 13 + 1 + + + TTC + TTC + 14 + 3 + + + FTF + FTF + 20 + 1 + + + TSF + TSF + 21 + 1 + + + DFRF + DFRF + 24 + 1 + + + RSF + RSF + 25 + 1 + + + DTCEFD + DTCEFD + 26 + 1 + + + + + DMAIER + DMAIER + Ethernet DMA interrupt enable + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + TIE + 0 + 1 + + + TPSIE + TPSIE + 1 + 1 + + + TBUIE + TBUIE + 2 + 1 + + + TJTIE + TJTIE + 3 + 1 + + + ROIE + ROIE + 4 + 1 + + + TUIE + TUIE + 5 + 1 + + + RIE + RIE + 6 + 1 + + + RBUIE + RBUIE + 7 + 1 + + + RPSIE + RPSIE + 8 + 1 + + + RWTIE + RWTIE + 9 + 1 + + + ETIE + ETIE + 10 + 1 + + + FBEIE + FBEIE + 13 + 1 + + + ERIE + ERIE + 14 + 1 + + + AISE + AISE + 15 + 1 + + + NISE + NISE + 16 + 1 + + + + + DMAMFBOCR + DMAMFBOCR + Ethernet DMA missed frame and buffer + overflow counter register + 0x20 + 0x20 + read-write + 0x00000000 + + + MFC + MFC + 0 + 16 + + + OMFC + OMFC + 16 + 1 + + + MFA + MFA + 17 + 11 + + + OFOC + OFOC + 28 + 1 + + + + + DMARSWTR + DMARSWTR + Ethernet DMA receive status watchdog timer + register + 0x24 + 0x20 + read-write + 0x00000000 + + + RSWTC + RSWTC + 0 + 8 + + + + + DMACHTDR + DMACHTDR + Ethernet DMA current host transmit + descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + HTDAP + 0 + 32 + + + + + DMACHRDR + DMACHRDR + Ethernet DMA current host receive descriptor + register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + HRDAP + 0 + 32 + + + + + DMACHTBAR + DMACHTBAR + Ethernet DMA current host transmit buffer + address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + HTBAP + 0 + 32 + + + + + DMACHRBAR + DMACHRBAR + Ethernet DMA current host receive buffer + address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + HRBAP + 0 + 32 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + INIT + INIT + Initial CRC value + 0xC + 0x20 + read-write + 0x00000000 + + + CRC_INIT + Programmable initial CRC + value + 0 + 32 + + + + + POL + POL + CRC polynomial + 0x10 + 0x20 + read-write + 0x00000000 + + + POL + Programmable polynomial + 0 + 32 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2SB + 8 + 6 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + read-write + 0x00000000 + + + LATENCY + Latency + 0 + 4 + + + PRFTEN + Prefetch enable + 8 + 1 + + + ARTEN + ART Accelerator Enable + 9 + 1 + + + ARTRST + ART Accelerator reset + 11 + 1 + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + ERSERR + Erase Sequence Error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase of sectors 0 to + 11 + 2 + 1 + + + SNB + Sector number + 3 + 5 + + + PSIZE + Program size + 8 + 2 + + + MER1 + Mass Erase of sectors 12 to + 23 + 15 + 1 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x0FFFAAED + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WWDG_SW + User option bytes + 4 + 1 + + + IWDG_SW + User option bytes + 5 + 1 + + + nRST_STOP + User option bytes + 6 + 1 + + + nRST_STDBY + User option bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 12 + + + nDBOOT + Dual Boot mode (valid only when + nDBANK=0) + 28 + 1 + + + nDBANK + Not dual bank mode + 29 + 1 + + + IWDG_STDBY + Independent watchdog counter freeze in + standby mode + 30 + 1 + + + IWDG_STOP + Independent watchdog counter freeze in + Stop mode + 31 + 1 + + + + + OPTCR1 + OPTCR1 + Flash option control register + 1 + 0x18 + 0x20 + read-write + 0x0FFF0000 + + + BOOT_ADD0 + Boot base address when Boot pin + =0 + 0 + 16 + + + BOOT_ADD1 + Boot base address when Boot pin + =1 + 16 + 16 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + LTDC + LCD-TFT Controller + LTDC + 0x40016800 + + 0x0 + 0x400 + registers + + + LCD_TFT + LTDC global interrupt + 88 + + + LTDC_ER + LTDC Error global interrupt + 89 + + + + SSCR + SSCR + Synchronization Size Configuration + Register + 0x8 + 0x20 + read-write + 0x00000000 + + + HSW + Horizontal Synchronization Width (in + units of pixel clock period) + 16 + 10 + + + VSH + Vertical Synchronization Height (in + units of horizontal scan line) + 0 + 11 + + + + + BPCR + BPCR + Back Porch Configuration + Register + 0xC + 0x20 + read-write + 0x00000000 + + + AHBP + Accumulated Horizontal back porch (in + units of pixel clock period) + 16 + 10 + + + AVBP + Accumulated Vertical back porch (in + units of horizontal scan line) + 0 + 11 + + + + + AWCR + AWCR + Active Width Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + AAV + AAV + 16 + 10 + + + AAH + Accumulated Active Height (in units of + horizontal scan line) + 0 + 11 + + + + + TWCR + TWCR + Total Width Configuration + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTALW + Total Width (in units of pixel clock + period) + 16 + 10 + + + TOTALH + Total Height (in units of horizontal + scan line) + 0 + 11 + + + + + GCR + GCR + Global Control Register + 0x18 + 0x20 + 0x00002220 + + + HSPOL + Horizontal Synchronization + Polarity + 31 + 1 + read-write + + + VSPOL + Vertical Synchronization + Polarity + 30 + 1 + read-write + + + DEPOL + Data Enable Polarity + 29 + 1 + read-write + + + PCPOL + Pixel Clock Polarity + 28 + 1 + read-write + + + DEN + Dither Enable + 16 + 1 + read-write + + + DRW + Dither Red Width + 12 + 3 + read-only + + + DGW + Dither Green Width + 8 + 3 + read-only + + + DBW + Dither Blue Width + 4 + 3 + read-only + + + LTDCEN + LCD-TFT controller enable + bit + 0 + 1 + read-write + + + + + SRCR + SRCR + Shadow Reload Configuration + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + VBR + Vertical Blanking Reload + 1 + 1 + + + IMR + Immediate Reload + 0 + 1 + + + + + BCCR + BCCR + Background Color Configuration + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BC + Background Color Red value + 0 + 24 + + + + + IER + IER + Interrupt Enable Register + 0x34 + 0x20 + read-write + 0x00000000 + + + RRIE + Register Reload interrupt + enable + 3 + 1 + + + TERRIE + Transfer Error Interrupt + Enable + 2 + 1 + + + FUIE + FIFO Underrun Interrupt + Enable + 1 + 1 + + + LIE + Line Interrupt Enable + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x38 + 0x20 + read-only + 0x00000000 + + + RRIF + Register Reload Interrupt + Flag + 3 + 1 + + + TERRIF + Transfer Error interrupt + flag + 2 + 1 + + + FUIF + FIFO Underrun Interrupt + flag + 1 + 1 + + + LIF + Line Interrupt flag + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x3C + 0x20 + write-only + 0x00000000 + + + CRRIF + Clears Register Reload Interrupt + Flag + 3 + 1 + + + CTERRIF + Clears the Transfer Error Interrupt + Flag + 2 + 1 + + + CFUIF + Clears the FIFO Underrun Interrupt + flag + 1 + 1 + + + CLIF + Clears the Line Interrupt + Flag + 0 + 1 + + + + + LIPCR + LIPCR + Line Interrupt Position Configuration + Register + 0x40 + 0x20 + read-write + 0x00000000 + + + LIPOS + Line Interrupt Position + 0 + 11 + + + + + CPSR + CPSR + Current Position Status + Register + 0x44 + 0x20 + read-only + 0x00000000 + + + CXPOS + Current X Position + 16 + 16 + + + CYPOS + Current Y Position + 0 + 16 + + + + + CDSR + CDSR + Current Display Status + Register + 0x48 + 0x20 + read-only + 0x0000000F + + + HSYNCS + Horizontal Synchronization display + Status + 3 + 1 + + + VSYNCS + Vertical Synchronization display + Status + 2 + 1 + + + HDES + Horizontal Data Enable display + Status + 1 + 1 + + + VDES + Vertical Data Enable display + Status + 0 + 1 + + + + + L1CR + L1CR + Layerx Control Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L1WHPCR + L1WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x88 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L1WVPCR + L1WVPCR + Layerx Window Vertical Position + Configuration Register + 0x8C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L1CKCR + L1CKCR + Layerx Color Keying Configuration + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L1PFCR + L1PFCR + Layerx Pixel Format Configuration + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L1CACR + L1CACR + Layerx Constant Alpha Configuration + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L1DCCR + L1DCCR + Layerx Default Color Configuration + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L1BFCR + L1BFCR + Layerx Blending Factors Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L1CFBAR + L1CFBAR + Layerx Color Frame Buffer Address + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L1CFBLR + L1CFBLR + Layerx Color Frame Buffer Length + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L1CFBLNR + L1CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L1CLUTWR + L1CLUTWR + Layerx CLUT Write Register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + L2CR + L2CR + Layerx Control Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L2WHPCR + L2WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x108 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L2WVPCR + L2WVPCR + Layerx Window Vertical Position + Configuration Register + 0x10C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L2CKCR + L2CKCR + Layerx Color Keying Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 15 + 9 + + + CKGREEN + Color Key Green value + 8 + 7 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L2PFCR + L2PFCR + Layerx Pixel Format Configuration + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L2CACR + L2CACR + Layerx Constant Alpha Configuration + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L2DCCR + L2DCCR + Layerx Default Color Configuration + Register + 0x11C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L2BFCR + L2BFCR + Layerx Blending Factors Configuration + Register + 0x120 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L2CFBAR + L2CFBAR + Layerx Color Frame Buffer Address + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L2CFBLR + L2CFBLR + Layerx Color Frame Buffer Length + Register + 0x130 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L2CFBLNR + L2CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0x134 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L2CLUTWR + L2CLUTWR + Layerx CLUT Write Register + 0x144 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + + + SAI1 + Serial audio interface + SAI + 0x40015800 + + 0x0 + 0x400 + registers + + + SAI1 + SAI1 global interrupt + 87 + + + + BCR1 + BCR1 + BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIBEN + Audio block B enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + BCR2 + BCR2 + BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + BFRCR + BFRCR + BFRCR + 0x2C + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + BSLOTR + BSLOTR + BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + BIM + BIM + BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + BSR + BSR + BStatus register + 0x38 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + BCLRFR + BCLRFR + BClear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + BDR + BDR + BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + ACR1 + ACR1 + AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIAEN + Audio block A enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + ACR2 + ACR2 + AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + AFRCR + AFRCR + AFRCR + 0xC + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + ASLOTR + ASLOTR + ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + AIM + AIM + AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + LFSDET + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + ASR + ASR + AStatus register + 0x18 + 0x20 + read-write + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + ACLRFR + ACLRFR + AClear flag register + 0x1C + 0x20 + read-write + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + ADR + ADR + AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + GCR + GCR + Global configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + SYNCIN + Synchronization inputs + 0 + 2 + + + SYNCOUT + Synchronization outputs + 4 + 2 + + + + + + + SAI2 + 0x40015C00 + + + DMA2D + DMA2D controller + DMA2D + 0x4002B000 + + 0x0 + 0xC00 + registers + + + DMA2D + DMA2D global interrupt + 90 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODE + DMA2D mode + 16 + 2 + + + CEIE + Configuration Error Interrupt + Enable + 13 + 1 + + + CTCIE + CLUT transfer complete interrupt + enable + 12 + 1 + + + CAEIE + CLUT access error interrupt + enable + 11 + 1 + + + TWIE + Transfer watermark interrupt + enable + 10 + 1 + + + TCIE + Transfer complete interrupt + enable + 9 + 1 + + + TEIE + Transfer error interrupt + enable + 8 + 1 + + + ABORT + Abort + 2 + 1 + + + SUSP + Suspend + 1 + 1 + + + START + Start + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x4 + 0x20 + read-only + 0x00000000 + + + CEIF + Configuration error interrupt + flag + 5 + 1 + + + CTCIF + CLUT transfer complete interrupt + flag + 4 + 1 + + + CAEIF + CLUT access error interrupt + flag + 3 + 1 + + + TWIF + Transfer watermark interrupt + flag + 2 + 1 + + + TCIF + Transfer complete interrupt + flag + 1 + 1 + + + TEIF + Transfer error interrupt + flag + 0 + 1 + + + + + IFCR + IFCR + interrupt flag clear register + 0x8 + 0x20 + read-write + 0x00000000 + + + CCEIF + Clear configuration error interrupt + flag + 5 + 1 + + + CCTCIF + Clear CLUT transfer complete interrupt + flag + 4 + 1 + + + CAECIF + Clear CLUT access error interrupt + flag + 3 + 1 + + + CTWIF + Clear transfer watermark interrupt + flag + 2 + 1 + + + CTCIF + Clear transfer complete interrupt + flag + 1 + 1 + + + CTEIF + Clear Transfer error interrupt + flag + 0 + 1 + + + + + FGMAR + FGMAR + foreground memory address + register + 0xC + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + FGOR + FGOR + foreground offset register + 0x10 + 0x20 + read-write + 0x00000000 + + + LO + Line offset + 0 + 14 + + + + + BGMAR + BGMAR + background memory address + register + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + BGOR + BGOR + background offset register + 0x18 + 0x20 + read-write + 0x00000000 + + + LO + Line offset + 0 + 14 + + + + + FGPFCCR + FGPFCCR + foreground PFC control + register + 0x1C + 0x20 + read-write + 0x00000000 + + + ALPHA + Alpha value + 24 + 8 + + + AM + Alpha mode + 16 + 2 + + + CS + CLUT size + 8 + 8 + + + START + Start + 5 + 1 + + + CCM + CLUT color mode + 4 + 1 + + + CM + Color mode + 0 + 4 + + + + + FGCOLR + FGCOLR + foreground color register + 0x20 + 0x20 + read-write + 0x00000000 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + BGPFCCR + BGPFCCR + background PFC control + register + 0x24 + 0x20 + read-write + 0x00000000 + + + ALPHA + Alpha value + 24 + 8 + + + AM + Alpha mode + 16 + 2 + + + CS + CLUT size + 8 + 8 + + + START + Start + 5 + 1 + + + CCM + CLUT Color mode + 4 + 1 + + + CM + Color mode + 0 + 4 + + + + + BGCOLR + BGCOLR + background color register + 0x28 + 0x20 + read-write + 0x00000000 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + FGCMAR + FGCMAR + foreground CLUT memory address + register + 0x2C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address + 0 + 32 + + + + + BGCMAR + BGCMAR + background CLUT memory address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + OPFCCR + OPFCCR + output PFC control register + 0x34 + 0x20 + read-write + 0x00000000 + + + CM + Color mode + 0 + 3 + + + + + OCOLR + OCOLR + output color register + 0x38 + 0x20 + read-write + 0x00000000 + + + APLHA + Alpha Channel Value + 24 + 8 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + OMAR + OMAR + output memory address register + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address + 0 + 32 + + + + + OOR + OOR + output offset register + 0x40 + 0x20 + read-write + 0x00000000 + + + LO + Line Offset + 0 + 14 + + + + + NLR + NLR + number of line register + 0x44 + 0x20 + read-write + 0x00000000 + + + PL + Pixel per lines + 16 + 14 + + + NL + Number of lines + 0 + 16 + + + + + LWR + LWR + line watermark register + 0x48 + 0x20 + read-write + 0x00000000 + + + LW + Line watermark + 0 + 16 + + + + + AMTCR + AMTCR + AHB master timer configuration + register + 0x4C + 0x20 + read-write + 0x00000000 + + + DT + Dead Time + 8 + 8 + + + EN + Enable + 0 + 1 + + + + + FGCLUT + FGCLUT + FGCLUT + 0x400 + 0x20 + read-write + 0x00000000 + + + APLHA + APLHA + 24 + 8 + + + RED + RED + 16 + 8 + + + GREEN + GREEN + 8 + 8 + + + BLUE + BLUE + 0 + 8 + + + + + BGCLUT + BGCLUT + BGCLUT + 0x800 + 0x20 + read-write + 0x00000000 + + + APLHA + APLHA + 24 + 8 + + + RED + RED + 16 + 8 + + + GREEN + GREEN + 8 + 8 + + + BLUE + BLUE + 0 + 8 + + + + + + + QUADSPI + QuadSPI interface + QUADSPI + 0xA0001000 + + 0x0 + 0x1000 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PRESCALER + Clock prescaler + 24 + 8 + + + PMM + Polling match mode + 23 + 1 + + + APMS + Automatic poll mode stop + 22 + 1 + + + TOIE + TimeOut interrupt enable + 20 + 1 + + + SMIE + Status match interrupt + enable + 19 + 1 + + + FTIE + FIFO threshold interrupt + enable + 18 + 1 + + + TCIE + Transfer complete interrupt + enable + 17 + 1 + + + TEIE + Transfer error interrupt + enable + 16 + 1 + + + FTHRES + IFO threshold level + 8 + 5 + + + FSEL + FLASH memory selection + 7 + 1 + + + DFM + Dual-flash mode + 6 + 1 + + + SSHIFT + Sample shift + 4 + 1 + + + TCEN + Timeout counter enable + 3 + 1 + + + DMAEN + DMA enable + 2 + 1 + + + ABORT + Abort request + 1 + 1 + + + EN + Enable + 0 + 1 + + + + + DCR + DCR + device configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + FSIZE + FLASH memory size + 16 + 5 + + + CSHT + Chip select high time + 8 + 3 + + + CKMODE + Mode 0 / mode 3 + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + read-only + 0x00000000 + + + FLEVEL + FIFO level + 8 + 7 + + + BUSY + Busy + 5 + 1 + + + TOF + Timeout flag + 4 + 1 + + + SMF + Status match flag + 3 + 1 + + + FTF + FIFO threshold flag + 2 + 1 + + + TCF + Transfer complete flag + 1 + 1 + + + TEF + Transfer error flag + 0 + 1 + + + + + FCR + FCR + flag clear register + 0xC + 0x20 + read-write + 0x00000000 + + + CTOF + Clear timeout flag + 4 + 1 + + + CSMF + Clear status match flag + 3 + 1 + + + CTCF + Clear transfer complete + flag + 1 + 1 + + + CTEF + Clear transfer error flag + 0 + 1 + + + + + DLR + DLR + data length register + 0x10 + 0x20 + read-write + 0x00000000 + + + DL + Data length + 0 + 32 + + + + + CCR + CCR + communication configuration + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DDRM + Double data rate mode + 31 + 1 + + + DHHC + DDR hold half cycle + 30 + 1 + + + SIOO + Send instruction only once + mode + 28 + 1 + + + FMODE + Functional mode + 26 + 2 + + + DMODE + Data mode + 24 + 2 + + + DCYC + Number of dummy cycles + 18 + 5 + + + ABSIZE + Alternate bytes size + 16 + 2 + + + ABMODE + Alternate bytes mode + 14 + 2 + + + ADSIZE + Address size + 12 + 2 + + + ADMODE + Address mode + 10 + 2 + + + IMODE + Instruction mode + 8 + 2 + + + INSTRUCTION + Instruction + 0 + 8 + + + + + AR + AR + address register + 0x18 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Address + 0 + 32 + + + + + ABR + ABR + ABR + 0x1C + 0x20 + read-write + 0x00000000 + + + ALTERNATE + ALTERNATE + 0 + 32 + + + + + DR + DR + data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + PSMKR + PSMKR + polling status mask register + 0x24 + 0x20 + read-write + 0x00000000 + + + MASK + Status mask + 0 + 32 + + + + + PSMAR + PSMAR + polling status match register + 0x28 + 0x20 + read-write + 0x00000000 + + + MATCH + Status match + 0 + 32 + + + + + PIR + PIR + polling interval register + 0x2C + 0x20 + read-write + 0x00000000 + + + INTERVAL + Polling interval + 0 + 16 + + + + + LPTR + LPTR + low-power timeout register + 0x30 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Timeout period + 0 + 16 + + + + + + + CEC + HDMI-CEC controller + CEC + 0x40006C00 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + TXEOM + Tx End Of Message + 2 + 1 + + + TXSOM + Tx start of message + 1 + 1 + + + CECEN + CEC Enable + 0 + 1 + + + + + CFGR + CFGR + configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + SFT + Signal Free Time + 0 + 3 + + + RXTOL + Rx-Tolerance + 3 + 1 + + + BRESTP + Rx-stop on bit rising + error + 4 + 1 + + + BREGEN + Generate error-bit on bit rising + error + 5 + 1 + + + LBPEGEN + Generate Error-Bit on Long Bit Period + Error + 6 + 1 + + + BRDNOGEN + Avoid Error-Bit Generation in + Broadcast + 7 + 1 + + + SFTOP + SFT Option Bit + 8 + 1 + + + OAR + Own addresses + configuration + 16 + 15 + + + LSTN + Listen mode + 31 + 1 + + + + + TXDR + TXDR + Tx data register + 0x8 + 0x20 + write-only + 0x00000000 + + + TXD + Tx Data register + 0 + 8 + + + + + RXDR + RXDR + Rx Data Register + 0xC + 0x20 + read-only + 0x00000000 + + + RXDR + CEC Rx Data Register + 0 + 8 + + + + + ISR + ISR + Interrupt and Status Register + 0x10 + 0x20 + read-write + 0x00000000 + + + TXACKE + Tx-Missing acknowledge + error + 12 + 1 + + + TXERR + Tx-Error + 11 + 1 + + + TXUDR + Tx-Buffer Underrun + 10 + 1 + + + TXEND + End of Transmission + 9 + 1 + + + TXBR + Tx-Byte Request + 8 + 1 + + + ARBLST + Arbitration Lost + 7 + 1 + + + RXACKE + Rx-Missing Acknowledge + 6 + 1 + + + LBPE + Rx-Long Bit Period Error + 5 + 1 + + + SBPE + Rx-Short Bit period error + 4 + 1 + + + BRE + Rx-Bit rising error + 3 + 1 + + + RXOVR + Rx-Overrun + 2 + 1 + + + RXEND + End Of Reception + 1 + 1 + + + RXBR + Rx-Byte Received + 0 + 1 + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + TXACKIE + Tx-Missing Acknowledge Error Interrupt + Enable + 12 + 1 + + + TXERRIE + Tx-Error Interrupt Enable + 11 + 1 + + + TXUDRIE + Tx-Underrun interrupt + enable + 10 + 1 + + + TXENDIE + Tx-End of message interrupt + enable + 9 + 1 + + + TXBRIE + Tx-Byte Request Interrupt + Enable + 8 + 1 + + + ARBLSTIE + Arbitration Lost Interrupt + Enable + 7 + 1 + + + RXACKIE + Rx-Missing Acknowledge Error Interrupt + Enable + 6 + 1 + + + LBPEIE + Long Bit Period Error Interrupt + Enable + 5 + 1 + + + SBPEIE + Short Bit Period Error Interrupt + Enable + 4 + 1 + + + BREIE + Bit Rising Error Interrupt + Enable + 3 + 1 + + + RXOVRIE + Rx-Buffer Overrun Interrupt + Enable + 2 + 1 + + + RXENDIE + End Of Reception Interrupt + Enable + 1 + 1 + + + RXBRIE + Rx-Byte Received Interrupt + Enable + 0 + 1 + + + + + + + SPDIF_RX + Receiver Interface + SPDIF_RX + 0x40004000 + + 0x0 + 0x400 + registers + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x00000000 + + + SPDIFEN + Peripheral Block Enable + 0 + 2 + + + RXDMAEN + Receiver DMA ENable for data + flow + 2 + 1 + + + RXSTEO + STerEO Mode + 3 + 1 + + + DRFMT + RX Data format + 4 + 2 + + + PMSK + Mask Parity error bit + 6 + 1 + + + VMSK + Mask of Validity bit + 7 + 1 + + + CUMSK + Mask of channel status and user + bits + 8 + 1 + + + PTMSK + Mask of Preamble Type bits + 9 + 1 + + + CBDMAEN + Control Buffer DMA ENable for control + flow + 10 + 1 + + + CHSEL + Channel Selection + 11 + 1 + + + NBTR + Maximum allowed re-tries during + synchronization phase + 12 + 2 + + + WFA + Wait For Activity + 14 + 1 + + + INSEL + input selection + 16 + 3 + + + + + IMR + IMR + Interrupt mask register + 0x4 + 0x20 + read-write + 0x00000000 + + + RXNEIE + RXNE interrupt enable + 0 + 1 + + + CSRNEIE + Control Buffer Ready Interrupt + Enable + 1 + 1 + + + PERRIE + Parity error interrupt + enable + 2 + 1 + + + OVRIE + Overrun error Interrupt + Enable + 3 + 1 + + + SBLKIE + Synchronization Block Detected Interrupt + Enable + 4 + 1 + + + SYNCDIE + Synchronization Done + 5 + 1 + + + IFEIE + Serial Interface Error Interrupt + Enable + 6 + 1 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-only + 0x00000000 + + + RXNE + Read data register not + empty + 0 + 1 + + + CSRNE + Control Buffer register is not + empty + 1 + 1 + + + PERR + Parity error + 2 + 1 + + + OVR + Overrun error + 3 + 1 + + + SBD + Synchronization Block + Detected + 4 + 1 + + + SYNCD + Synchronization Done + 5 + 1 + + + FERR + Framing error + 6 + 1 + + + SERR + Synchronization error + 7 + 1 + + + TERR + Time-out error + 8 + 1 + + + WIDTH5 + Duration of 5 symbols counted with + SPDIF_CLK + 16 + 15 + + + + + IFCR + IFCR + Interrupt Flag Clear register + 0xC + 0x20 + write-only + 0x00000000 + + + PERRCF + Clears the Parity error + flag + 2 + 1 + + + OVRCF + Clears the Overrun error + flag + 3 + 1 + + + SBDCF + Clears the Synchronization Block + Detected flag + 4 + 1 + + + SYNCDCF + Clears the Synchronization Done + flag + 5 + 1 + + + + + DR + DR + Data input register + 0x10 + 0x20 + read-only + 0x00000000 + + + DR + Parity Error bit + 0 + 24 + + + PE + Parity Error bit + 24 + 1 + + + V + Validity bit + 25 + 1 + + + U + User bit + 26 + 1 + + + C + Channel Status bit + 27 + 1 + + + PT + Preamble Type + 28 + 2 + + + + + CSR + CSR + Channel Status register + 0x14 + 0x20 + read-only + 0x00000000 + + + USR + User data information + 0 + 16 + + + CS + Channel A status + information + 16 + 8 + + + SOB + Start Of Block + 24 + 1 + + + + + DIR + DIR + Debug Information register + 0x18 + 0x20 + read-only + 0x00000000 + + + THI + Threshold HIGH + 0 + 13 + + + TLO + Threshold LOW + 16 + 13 + + + + + + + SDMMC1 + Secure digital input/output + interface + SDMMC + 0x40012C00 + + 0x0 + 0x400 + registers + + + SDMMC1 + SDMMC1 global interrupt + 49 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + CE_ATACMD + CE-ATA command + 14 + 1 + + + nIEN + not Interrupt Enable + 13 + 1 + + + ENCMDcompl + Enable CMD completion + 12 + 1 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal) + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 132 + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table 132 + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table 132 + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table 132 + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + CEATAEND + CE-ATA command completion signal + received for CMD61 + 23 + 1 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + STBITERR + Start bit not detected on all data + signals in wide bus mode + 9 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEATAENDC + CEATAEND flag clear bit + 23 + 1 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + STBITERRC + STBITERR flag clear bit + 9 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + CEATAENDIE + CE-ATA command completion signal + received interrupt enable + 23 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + STBITERRIE + Start bit error interrupt + enable + 9 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + LPTIM1 + Low power timer + LPTIM + 0x40002400 + + 0x0 + 0x400 + registers + + + + ISR + ISR + Interrupt and Status Register + 0x0 + 0x20 + read-only + 0x00000000 + + + DOWN + Counter direction change up to + down + 6 + 1 + + + UP + Counter direction change down to + up + 5 + 1 + + + ARROK + Autoreload register update + OK + 4 + 1 + + + CMPOK + Compare register update OK + 3 + 1 + + + EXTTRIG + External trigger edge + event + 2 + 1 + + + ARRM + Autoreload match + 1 + 1 + + + CMPM + Compare match + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x4 + 0x20 + write-only + 0x00000000 + + + DOWNCF + Direction change to down Clear + Flag + 6 + 1 + + + UPCF + Direction change to UP Clear + Flag + 5 + 1 + + + ARROKCF + Autoreload register update OK Clear + Flag + 4 + 1 + + + CMPOKCF + Compare register update OK Clear + Flag + 3 + 1 + + + EXTTRIGCF + External trigger valid edge Clear + Flag + 2 + 1 + + + ARRMCF + Autoreload match Clear + Flag + 1 + 1 + + + CMPMCF + compare match Clear Flag + 0 + 1 + + + + + IER + IER + Interrupt Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + DOWNIE + Direction change to down Interrupt + Enable + 6 + 1 + + + UPIE + Direction change to UP Interrupt + Enable + 5 + 1 + + + ARROKIE + Autoreload register update OK Interrupt + Enable + 4 + 1 + + + CMPOKIE + Compare register update OK Interrupt + Enable + 3 + 1 + + + EXTTRIGIE + External trigger valid edge Interrupt + Enable + 2 + 1 + + + ARRMIE + Autoreload match Interrupt + Enable + 1 + 1 + + + CMPMIE + Compare match Interrupt + Enable + 0 + 1 + + + + + CFGR + CFGR + Configuration Register + 0xC + 0x20 + read-write + 0x00000000 + + + ENC + Encoder mode enable + 24 + 1 + + + COUNTMODE + counter mode enabled + 23 + 1 + + + PRELOAD + Registers update mode + 22 + 1 + + + WAVPOL + Waveform shape polarity + 21 + 1 + + + WAVE + Waveform shape + 20 + 1 + + + TIMOUT + Timeout enable + 19 + 1 + + + TRIGEN + Trigger enable and + polarity + 17 + 2 + + + TRIGSEL + Trigger selector + 13 + 3 + + + PRESC + Clock prescaler + 9 + 3 + + + TRGFLT + Configurable digital filter for + trigger + 6 + 2 + + + CKFLT + Configurable digital filter for external + clock + 3 + 2 + + + CKPOL + Clock Polarity + 1 + 2 + + + CKSEL + Clock selector + 0 + 1 + + + + + CR + CR + Control Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTSTRT + Timer start in continuous + mode + 2 + 1 + + + SNGSTRT + LPTIM start in single mode + 1 + 1 + + + ENABLE + LPTIM Enable + 0 + 1 + + + + + CMP + CMP + Compare Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CMP + Compare value + 0 + 16 + + + + + ARR + ARR + Autoreload Register + 0x18 + 0x20 + read-write + 0x00000001 + + + ARR + Auto reload value + 0 + 16 + + + + + CNT + CNT + Counter Register + 0x1C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 16 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + PE + Peripheral enable + 0 + 1 + + + TXIE + TX Interrupt enable + 1 + 1 + + + RXIE + RX Interrupt enable + 2 + 1 + + + ADDRIE + Address match interrupt enable (slave + only) + 3 + 1 + + + NACKIE + Not acknowledge received interrupt + enable + 4 + 1 + + + STOPIE + STOP detection Interrupt + enable + 5 + 1 + + + TCIE + Transfer Complete interrupt + enable + 6 + 1 + + + ERRIE + Error interrupts enable + 7 + 1 + + + DNF + Digital noise filter + 8 + 4 + + + ANFOFF + Analog noise filter OFF + 12 + 1 + + + TXDMAEN + DMA transmission requests + enable + 14 + 1 + + + RXDMAEN + DMA reception requests + enable + 15 + 1 + + + SBC + Slave byte control + 16 + 1 + + + NOSTRETCH + Clock stretching disable + 17 + 1 + + + WUPEN + Wakeup from STOP enable + 18 + 1 + + + GCEN + General call enable + 19 + 1 + + + SMBHEN + SMBus Host address enable + 20 + 1 + + + SMBDEN + SMBus Device Default address + enable + 21 + 1 + + + ALERTEN + SMBUS alert enable + 22 + 1 + + + PECEN + PEC enable + 23 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECBYTE + Packet error checking byte + 26 + 1 + + + AUTOEND + Automatic end mode (master + mode) + 25 + 1 + + + RELOAD + NBYTES reload mode + 24 + 1 + + + NBYTES + Number of bytes + 16 + 8 + + + NACK + NACK generation (slave + mode) + 15 + 1 + + + STOP + Stop generation (master + mode) + 14 + 1 + + + START + Start generation + 13 + 1 + + + HEAD10R + 10-bit address header only read + direction (master receiver mode) + 12 + 1 + + + ADD10 + 10-bit addressing mode (master + mode) + 11 + 1 + + + RD_WRN + Transfer direction (master + mode) + 10 + 1 + + + SADD + Slave address bit (master + mode) + 0 + 10 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + OA1 + Interface address + 0 + 10 + + + OA1MODE + Own Address 1 10-bit mode + 10 + 1 + + + OA1EN + Own Address 1 enable + 15 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + OA2 + Interface address + 1 + 7 + + + OA2MSK + Own Address 2 masks + 8 + 3 + + + OA2EN + Own Address 2 enable + 15 + 1 + + + + + TIMINGR + TIMINGR + Timing register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low period (master + mode) + 0 + 8 + + + SCLH + SCL high period (master + mode) + 8 + 8 + + + SDADEL + Data hold time + 16 + 4 + + + SCLDEL + Data setup time + 20 + 4 + + + PRESC + Timing prescaler + 28 + 4 + + + + + TIMEOUTR + TIMEOUTR + Status register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + TIMEOUTA + Bus timeout A + 0 + 12 + + + TIDLE + Idle clock timeout + detection + 12 + 1 + + + TIMOUTEN + Clock timeout enable + 15 + 1 + + + TIMEOUTB + Bus timeout B + 16 + 12 + + + TEXTEN + Extended clock timeout + enable + 31 + 1 + + + + + ISR + ISR + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDCODE + Address match code (Slave + mode) + 17 + 7 + read-only + + + DIR + Transfer direction (Slave + mode) + 16 + 1 + read-only + + + BUSY + Bus busy + 15 + 1 + read-only + + + ALERT + SMBus alert + 13 + 1 + read-only + + + TIMEOUT + Timeout or t_low detection + flag + 12 + 1 + read-only + + + PECERR + PEC Error in reception + 11 + 1 + read-only + + + OVR + Overrun/Underrun (slave + mode) + 10 + 1 + read-only + + + ARLO + Arbitration lost + 9 + 1 + read-only + + + BERR + Bus error + 8 + 1 + read-only + + + TCR + Transfer Complete Reload + 7 + 1 + read-only + + + TC + Transfer Complete (master + mode) + 6 + 1 + read-only + + + STOPF + Stop detection flag + 5 + 1 + read-only + + + NACKF + Not acknowledge received + flag + 4 + 1 + read-only + + + ADDR + Address matched (slave + mode) + 3 + 1 + read-only + + + RXNE + Receive data register not empty + (receivers) + 2 + 1 + read-only + + + TXIS + Transmit interrupt status + (transmitters) + 1 + 1 + read-write + + + TXE + Transmit data register empty + (transmitters) + 0 + 1 + read-write + + + + + ICR + ICR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTCF + Alert flag clear + 13 + 1 + + + TIMOUTCF + Timeout detection flag + clear + 12 + 1 + + + PECCF + PEC Error flag clear + 11 + 1 + + + OVRCF + Overrun/Underrun flag + clear + 10 + 1 + + + ARLOCF + Arbitration lost flag + clear + 9 + 1 + + + BERRCF + Bus error flag clear + 8 + 1 + + + STOPCF + Stop detection flag clear + 5 + 1 + + + NACKCF + Not Acknowledge flag clear + 4 + 1 + + + ADDRCF + Address Matched flag clear + 3 + 1 + + + + + PECR + PECR + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PEC + Packet error checking + register + 0 + 8 + + + + + RXDR + RXDR + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + RXDATA + 8-bit receive data + 0 + 8 + + + + + TXDR + TXDR + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + TXDATA + 8-bit transmit data + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + + I2C3 + 0x40005C00 + + + I2C4 + 0x40006000 + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Tamper or TimeStamp /CSS on LSE through + EXTI line 19 interrupts + 3 + + + RTC_ALARM + RTC alarms through EXTI line 18 + interrupts + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + BYPSHAD + Bypass the shadow + registers + 5 + 1 + + + FMT + Hour format + 6 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + BKP + Backup + 18 + 1 + + + COSEL + Calibration output + selection + 19 + 1 + + + POL + Output polarity + 20 + 1 + + + OSEL + Output selection + 21 + 2 + + + COE + Calibration output enable + 23 + 1 + + + ITSE + timestamp on internal event + enable + 24 + 1 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + RTC_TAMP2 detection flag + 14 + 1 + read-write + + + TAMP3F + RTC_TAMP3 detection flag + 15 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAMPCR + TAMPCR + tamper configuration register + 0x40 + 0x20 + read-write + 0x00000000 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP3E + Tamper 3 detection enable + 5 + 1 + + + TAMP3TRG + Active level for tamper 3 + 6 + 1 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMP1IE + Tamper 1 interrupt enable + 16 + 1 + + + TAMP1NOERASE + Tamper 1 no erase + 17 + 1 + + + TAMP1MF + Tamper 1 mask flag + 18 + 1 + + + TAMP2IE + Tamper 2 interrupt enable + 19 + 1 + + + TAMP2NOERASE + Tamper 2 no erase + 20 + 1 + + + TAMP2MF + Tamper 2 mask flag + 21 + 1 + + + TAMP3IE + Tamper 3 interrupt enable + 22 + 1 + + + TAMP3NOERASE + Tamper 3 no erase + 23 + 1 + + + TAMP3MF + Tamper 3 mask flag + 24 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + OR + OR + option register + 0x4C + 0x20 + read-write + 0x00000000 + + + RTC_ALARM_TYPE + RTC_ALARM on PC13 output + type + 0 + 1 + + + RTC_OUT_RMP + RTC_OUT remap + 1 + 1 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP20R + BKP20R + backup register + 0xA0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP21R + BKP21R + backup register + 0xA4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP22R + BKP22R + backup register + 0xA8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP23R + BKP23R + backup register + 0xAC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP24R + BKP24R + backup register + 0xB0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP25R + BKP25R + backup register + 0xB4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP26R + BKP26R + backup register + 0xB8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP27R + BKP27R + backup register + 0xBC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP28R + BKP28R + backup register + 0xC0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP29R + BKP29R + backup register + 0xC4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP30R + BKP30R + backup register + 0xC8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP31R + BKP31R + backup register + 0xCC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + USART6 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011400 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + M1 + Word length + 28 + 1 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT4 + Driver Enable assertion + time + 25 + 1 + + + DEAT3 + DEAT3 + 24 + 1 + + + DEAT2 + DEAT2 + 23 + 1 + + + DEAT1 + DEAT1 + 22 + 1 + + + DEAT0 + DEAT0 + 21 + 1 + + + DEDT4 + Driver Enable de-assertion + time + 20 + 1 + + + DEDT3 + DEDT3 + 19 + 1 + + + DEDT2 + DEDT2 + 18 + 1 + + + DEDT1 + DEDT1 + 17 + 1 + + + DEDT0 + DEDT0 + 16 + 1 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UESM + USART enable in Stop mode + 1 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4_7 + Address of the USART node + 28 + 4 + + + ADD0_3 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD1 + Auto baud rate mode + 22 + 1 + + + ABRMOD0 + ABRMOD0 + 21 + 1 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + TAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + WUFIE + Wakeup from Stop mode interrupt + enable + 22 + 1 + + + WUS + Wakeup from Stop mode interrupt flag + selection + 20 + 2 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + Ir low-power + 2 + 1 + + + IREN + Ir mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + DIV_Mantissa + 4 + 12 + + + DIV_Fraction + DIV_Fraction + 0 + 4 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + REACK + REACK + 22 + 1 + + + TEACK + TEACK + 21 + 1 + + + WUF + WUF + 20 + 1 + + + RWU + RWU + 19 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + ABRF + ABRF + 15 + 1 + + + ABRE + ABRE + 14 + 1 + + + EOBF + EOBF + 12 + 1 + + + RTOF + RTOF + 11 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + LBDF + LBDF + 8 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NF + NF + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + WUCF + Wakeup from Stop mode clear + flag + 20 + 1 + + + CMCF + Character match clear flag + 17 + 1 + + + EOBCF + End of block clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + + + USART1 + 0x40011000 + + USART1 + USART1 global interrupt + 37 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + UART4 + 0x40004C00 + + + UART8 + 0x40007C00 + + UART8 + UART 8 global interrupt + 83 + + + + UART7 + 0x40007800 + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + + OTG_FS_GOTGCTL + OTG_FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + VBVALOEN + VBUS valid override enable + 2 + 1 + read-write + + + VBVALOVAL + VBUS valid override value + 3 + 1 + read-write + + + AVALOEN + A-peripheral session valid override + enable + 4 + 1 + read-write + + + AVALOVAL + A-peripheral session valid override + value + 5 + 1 + read-write + + + BVALOEN + B-peripheral session valid override + enable + 6 + 1 + read-write + + + BVALOVAL + B-peripheral session valid override + value + 7 + 1 + read-write + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + OTGVER + OTG version + 20 + 1 + read-write + + + + + OTG_FS_GOTGINT + OTG_FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_FS_GAHBCFG + OTG_FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_FS_GUSBCFG + OTG_FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + + + OTG_FS_GRSTCTL + OTG_FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_FS_GINTSTS + OTG_FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + RSTDET + Reset detected interrupt + 23 + 1 + read-write + + + + + OTG_FS_GINTMSK + OTG_FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDETM + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMIN + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_FS_GRXSTSR_Device + OTG_FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSR_Host + OTG_FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + OTG_FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GRXFSIZ + OTG_FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_FS_DIEPTXF0_Device + OTG_FS_DIEPTXF0_Device + OTG_FS Endpoint 0 Transmit FIFO + size + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXFSIZ_Host + OTG_FS_HNPTXFSIZ_Host + OTG_FS Host non-periodic transmit FIFO size + register + OTG_FS_DIEPTXF0_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXSTS + OTG_FS_HNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + OTG_FS_GCCFG + OTG_FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_FS_CID + OTG_FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_FS_HPTXFSIZ + OTG_FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF1 + OTG_FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF2 + OTG_FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF3 + OTG_FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_GRXSTSP_Device + OTG_FS_GRXSTSP_Device + OTG status read and pop register (Device + mode) + 0x20 + 0x20 + read-only + 0x02000400 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSP_Host + OTG_FS_GRXSTSP_Host + OTG status read and pop register (Host + mode) + OTG_FS_GRXSTSP_Device + 0x20 + 0x20 + read-only + 0x02000400 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GI2CCTL + OTG_FS_GI2CCTL + OTG I2C access register + 0x30 + 0x20 + read-write + 0x02000400 + + + RWDATA + I2C Read/Write Data + 0 + 8 + + + REGADDR + I2C Register Address + 8 + 8 + + + ADDR + I2C Address + 16 + 7 + + + I2CEN + I2C Enable + 23 + 1 + + + ACK + I2C ACK + 24 + 1 + + + I2CDEVADR + I2C Device Address + 26 + 2 + + + I2CDATSE0 + I2C DatSe0 USB mode + 28 + 1 + + + RW + Read/Write Indicator + 30 + 1 + + + BSYDNE + I2C Busy/Done + 31 + 1 + + + + + OTG_FS_GPWRDN + OTG_FS_GPWRDN + OTG power down register + 0x58 + 0x20 + read-write + 0x02000400 + + + ADPMEN + ADP module enable + 0 + 1 + + + ADPIF + ADP interrupt flag + 23 + 1 + + + + + OTG_FS_GADPCTL + OTG_FS_GADPCTL + OTG ADP timer, control and status + register + 0x60 + 0x20 + 0x02000400 + + + PRBDSCHG + Probe discharge + 0 + 2 + read-write + + + PRBDELTA + Probe delta + 2 + 2 + read-write + + + PRBPER + Probe period + 4 + 2 + read-write + + + RTIM + Ramp time + 6 + 11 + read-only + + + ENAPRB + Enable probe + 17 + 1 + read-write + + + ENASNS + Enable sense + 18 + 1 + read-write + + + ADPRST + ADP reset + 19 + 1 + read-only + + + ADPEN + ADP enable + 20 + 1 + read-write + + + ADPPRBIF + ADP probe interrupt flag + 21 + 1 + read-write + + + ADPSNSIF + ADP sense interrupt flag + 22 + 1 + read-write + + + ADPTOIF + ADP timeout interrupt flag + 23 + 1 + read-write + + + ADPPRBIM + ADP probe interrupt mask + 24 + 1 + read-write + + + ADPSNSIM + ADP sense interrupt mask + 25 + 1 + read-write + + + ADPTOIM + ADP timeout interrupt mask + 26 + 1 + read-write + + + AR + Access request + 27 + 2 + read-write + + + + + OTG_FS_DIEPTXF4 + OTG_FS_DIEPTXF4 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF5 + OTG_FS_DIEPTXF5 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_GLPMCFG + OTG_FS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 0x20 + 0x02000400 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-write + + + REMWAKE + bRemoteWake value + 6 + 1 + read-write + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + + OTG_FS_HCFG + OTG_FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_FS_HFIR + OTG_FS_HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_FS_HFNUM + OTG_FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_FS_HPTXSTS + OTG_FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_FS_HAINT + OTG_FS_HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_FS_HAINTMSK + OTG_FS_HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_FS_HPRT + OTG_FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_FS_HCCHAR0 + OTG_FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR1 + OTG_FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR2 + OTG_FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR3 + OTG_FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR4 + OTG_FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR5 + OTG_FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR6 + OTG_FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR7 + OTG_FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT0 + OTG_FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT1 + OTG_FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT2 + OTG_FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT3 + OTG_FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT4 + OTG_FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT5 + OTG_FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT6 + OTG_FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT7 + OTG_FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK0 + OTG_FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK1 + OTG_FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK2 + OTG_FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK3 + OTG_FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK4 + OTG_FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK5 + OTG_FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK6 + OTG_FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK7 + OTG_FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ0 + OTG_FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ1 + OTG_FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ2 + OTG_FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ3 + OTG_FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ4 + OTG_FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ5 + OTG_FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ6 + OTG_FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ7 + OTG_FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR8 + OTG_FS_HCCHAR8 + OTG_FS host channel-8 characteristics + register + 0x1F4 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT8 + OTG_FS_HCINT8 + OTG_FS host channel-8 interrupt + register + 0x1F8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK8 + OTG_FS_HCINTMSK8 + OTG_FS host channel-8 mask + register + 0x1FC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ8 + OTG_FS_HCTSIZ8 + OTG_FS host channel-8 transfer size + register + 0x200 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR9 + OTG_FS_HCCHAR9 + OTG_FS host channel-9 characteristics + register + 0x204 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT9 + OTG_FS_HCINT9 + OTG_FS host channel-9 interrupt + register + 0x208 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK9 + OTG_FS_HCINTMSK9 + OTG_FS host channel-9 mask + register + 0x20C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ9 + OTG_FS_HCTSIZ9 + OTG_FS host channel-9 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR10 + OTG_FS_HCCHAR10 + OTG_FS host channel-10 characteristics + register + 0x214 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT10 + OTG_FS_HCINT10 + OTG_FS host channel-10 interrupt + register + 0x218 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK10 + OTG_FS_HCINTMSK10 + OTG_FS host channel-10 mask + register + 0x21C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ10 + OTG_FS_HCTSIZ10 + OTG_FS host channel-10 transfer size + register + 0x220 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR11 + OTG_FS_HCCHAR11 + OTG_FS host channel-11 characteristics + register + 0x224 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT11 + OTG_FS_HCINT11 + OTG_FS host channel-11 interrupt + register + 0x228 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK11 + OTG_FS_HCINTMSK11 + OTG_FS host channel-11 mask + register + 0x22C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ11 + OTG_FS_HCTSIZ11 + OTG_FS host channel-11 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + OTG_FS_DCFG + OTG_FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + OTG_FS_DCTL + OTG_FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_FS_DSTS + OTG_FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_FS_DIEPMSK + OTG_FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + OTG_FS_DOEPMSK + OTG_FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + OTG_FS_DAINT + OTG_FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DAINTMSK + OTG_FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DVBUSDIS + OTG_FS_DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_FS_DVBUSPULSE + OTG_FS_DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_FS_DIEPEMPMSK + OTG_FS_DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_FS_DIEPCTL0 + OTG_FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + OTG_FS_DIEPCTL1 + OTG_FS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL2 + OTG_FS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL3 + OTG_FS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL0 + OTG_FS_DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + OTG_FS_DOEPCTL1 + OTG_FS_DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL2 + OTG_FS_DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL3 + OTG_FS_DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT0 + OTG_FS_DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT1 + OTG_FS_DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT2 + OTG_FS_DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT3 + OTG_FS_DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DOEPINT0 + OTG_FS_DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT1 + OTG_FS_DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT2 + OTG_FS_DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT3 + OTG_FS_DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DIEPTSIZ0 + OTG_FS_DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DOEPTSIZ0 + OTG_FS_DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DIEPTSIZ1 + OTG_FS_DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ2 + OTG_FS_DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ3 + OTG_FS_DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS0 + OTG_FS_DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS1 + OTG_FS_DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS2 + OTG_FS_DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS3 + OTG_FS_DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPTSIZ1 + OTG_FS_DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ2 + OTG_FS_DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ3 + OTG_FS_DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPCTL4 + OTG_FS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT4 + OTG_FS_DIEPINT4 + device endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ4 + OTG_FS_DIEPTSIZ4 + device endpoint-4 transfer size + register + 0x194 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS4 + OTG_FS_DTXFSTS4 + OTG_FS device IN endpoint transmit FIFO + status register + 0x19C + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DIEPCTL5 + OTG_FS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT5 + OTG_FS_DIEPINT5 + device endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ55 + OTG_FS_DIEPTSIZ55 + device endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS55 + OTG_FS_DTXFSTS55 + OTG_FS device IN endpoint transmit FIFO + status register + 0x1B8 + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPCTL4 + OTG_FS_DOEPCTL4 + device endpoint-4 control + register + 0x378 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT4 + OTG_FS_DOEPINT4 + device endpoint-4 interrupt + register + 0x380 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ4 + OTG_FS_DOEPTSIZ4 + device OUT endpoint-4 transfer size + register + 0x388 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPCTL5 + OTG_FS_DOEPCTL5 + device endpoint-5 control + register + 0x390 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT5 + OTG_FS_DOEPINT5 + device endpoint-5 interrupt + register + 0x398 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ5 + OTG_FS_DOEPTSIZ5 + device OUT endpoint-5 transfer size + register + 0x3A0 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + OTG_FS_PCGCCTL + OTG_FS_PCGCCTL + OTG_FS power and clock gating control + register (OTG_FS_PCGCCTL) + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + DMAREQ + DMA request signal enabled for USB OTG + HS + 30 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDE + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMINTM + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_HNPTXFSIZ_Host + OTG_HS_HNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF0_Device + OTG_HS_DIEPTXF0_Device + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_HNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Device + OTG_HS_GRXSTSR_Device + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Device + OTG_HS_GRXSTSP_Device + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GLPMCFG + OTG_HS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 32 + 0x0 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-only + + + REMWAKE + bRemoteWake value + 6 + 1 + read-only + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR12 + OTG_HS_HCCHAR12 + OTG_HS host channel-12 characteristics + register + 0x278 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT12 + OTG_HS_HCSPLT12 + OTG_HS host channel-12 split control + register + 0x27C + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT12 + OTG_HS_HCINT12 + OTG_HS host channel-12 interrupt + register + 0x280 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK12 + OTG_HS_HCINTMSK12 + OTG_HS host channel-12 interrupt mask + register + 0x284 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ12 + OTG_HS_HCTSIZ12 + OTG_HS host channel-12 transfer size + register + 0x288 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA12 + OTG_HS_HCDMA12 + OTG_HS host channel-12 DMA address + register + 0x28C + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR13 + OTG_HS_HCCHAR13 + OTG_HS host channel-13 characteristics + register + 0x290 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT13 + OTG_HS_HCSPLT13 + OTG_HS host channel-13 split control + register + 0x294 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT13 + OTG_HS_HCINT13 + OTG_HS host channel-13 interrupt + register + 0x298 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK13 + OTG_HS_HCINTMSK13 + OTG_HS host channel-13 interrupt mask + register + 0x29C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALLM response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ13 + OTG_HS_HCTSIZ13 + OTG_HS host channel-13 transfer size + register + 0x2A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA13 + OTG_HS_HCDMA13 + OTG_HS host channel-13 DMA address + register + 0x2A4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR14 + OTG_HS_HCCHAR14 + OTG_HS host channel-14 characteristics + register + 0x2A8 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT14 + OTG_HS_HCSPLT14 + OTG_HS host channel-14 split control + register + 0x2AC + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT14 + OTG_HS_HCINT14 + OTG_HS host channel-14 interrupt + register + 0x2B0 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK14 + OTG_HS_HCINTMSK14 + OTG_HS host channel-14 interrupt mask + register + 0x2B4 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAKM response received interrupt + mask + 4 + 1 + + + ACKM + ACKM response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ14 + OTG_HS_HCTSIZ14 + OTG_HS host channel-14 transfer size + register + 0x2B8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA14 + OTG_HS_HCDMA14 + OTG_HS host channel-14 DMA address + register + 0x2BC + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR15 + OTG_HS_HCCHAR15 + OTG_HS host channel-15 characteristics + register + 0x2C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT15 + OTG_HS_HCSPLT15 + OTG_HS host channel-15 split control + register + 0x2C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT15 + OTG_HS_HCINT15 + OTG_HS host channel-15 interrupt + register + 0x2C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK15 + OTG_HS_HCINTMSK15 + OTG_HS host channel-15 interrupt mask + register + 0x2CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ15 + OTG_HS_HCTSIZ15 + OTG_HS host channel-15 transfer size + register + 0x2D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA15 + OTG_HS_HCDMA15 + OTG_HS host channel-15 DMA address + register + 0x2D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-0 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-1 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-2 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-3 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-4 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ6 + OTG_HS_DIEPTSIZ6 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPCTL5 + 0x1A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS6 + OTG_HS_DTXFSTS6 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1A4 + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ7 + OTG_HS_DIEPTSIZ7 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPINT5 + 0x1A8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS7 + OTG_HS_DTXFSTS7 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1AC + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DOEPCTL4 + OTG_HS_DOEPCTL4 + OTG device endpoint-4 control + register + 0x380 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL5 + OTG_HS_DOEPCTL5 + OTG device endpoint-5 control + register + 0x3A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL6 + OTG_HS_DOEPCTL6 + OTG device endpoint-6 control + register + 0x3C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL7 + OTG_HS_DOEPCTL7 + OTG device endpoint-7 control + register + 0x3E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPTSIZ5 + OTG_HS_DOEPTSIZ5 + OTG_HS device endpoint-5 transfer size + register + 0x3B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ6 + OTG_HS_DOEPTSIZ6 + OTG_HS device endpoint-6 transfer size + register + 0x3D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ7 + OTG_HS_DOEPTSIZ7 + OTG_HS device endpoint-7 transfer size + register + 0x3F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + OTG_HS_EP1_OUT + USB On The Go HS End Point 1 Out global + interrupt + 74 + + + OTG_HS_EP1_IN + USB On The Go HS End Point 1 In global + interrupt + 75 + + + OTG_HS_WKUP + USB On The Go HS Wakeup through EXTI + interrupt + 76 + + + OTG_HS + USB On The Go HS global + interrupt + 77 + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CSR + CSR + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + RVR + RVR + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + CVR + CVR + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISFOLD + DISFOLD + 2 + 1 + + + FPEXCODIS + FPEXCODIS + 10 + 1 + + + DISRAMODE + DISRAMODE + 11 + 1 + + + DISITMATBFLUSH + DISITMATBFLUSH + 12 + 1 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + DC + DC + 16 + 1 + + + IC + IC + 17 + 1 + + + BP + BP + 18 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + IACCVIOL + 0 + 1 + + + DACCVIOL + DACCVIOL + 1 + 1 + + + MUNSTKERR + MUNSTKERR + 3 + 1 + + + MSTKERR + MSTKERR + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + MMARVALID + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Bus fault address + 0 + 32 + + + + + + + PF + Processor features + PF + 0xE000ED78 + + 0x0 + 0xD + registers + + + + CLIDR + CLIDR + Cache Level ID register + 0x0 + 0x20 + read-only + 0x09000003 + + + CL1 + CL1 + 0 + 3 + + + CL2 + CL2 + 3 + 3 + + + CL3 + CL3 + 6 + 3 + + + CL4 + CL4 + 9 + 3 + + + CL5 + CL5 + 12 + 3 + + + CL6 + CL6 + 15 + 3 + + + CL7 + CL7 + 18 + 3 + + + LoUIS + LoUIS + 21 + 3 + + + LoC + LoC + 24 + 3 + + + LoU + LoU + 27 + 3 + + + + + CTR + CTR + Cache Type register + 0x4 + 0x20 + read-only + 0X8303C003 + + + _IminLine + IminLine + 0 + 4 + + + DMinLine + DMinLine + 16 + 4 + + + ERG + ERG + 20 + 4 + + + CWG + CWG + 24 + 4 + + + Format + Format + 29 + 3 + + + + + CCSIDR + CCSIDR + Cache Size ID register + 0x8 + 0x20 + read-only + 0X00000000 + + + LineSize + LineSize + 0 + 3 + + + Associativity + Associativity + 3 + 10 + + + NumSets + NumSets + 13 + 15 + + + WA + WA + 28 + 1 + + + RA + RA + 29 + 1 + + + WB + WB + 30 + 1 + + + WT + WT + 31 + 1 + + + + + + + AC + Access control + AC + 0xE000EF90 + + 0x0 + 0x1D + registers + + + + ITCMCR + ITCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x0 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + DTCMCR + DTCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x4 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + AHBPCR + AHBPCR + AHBP Control register + 0x8 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + SZ + SZ + 1 + 3 + + + + + CACR + CACR + Auxiliary Cache Control + register + 0xC + 0x20 + read-write + 0X00000000 + + + SIWT + SIWT + 0 + 1 + + + ECCEN + ECCEN + 1 + 1 + + + FORCEWT + FORCEWT + 2 + 1 + + + + + AHBSCR + AHBSCR + AHB Slave Control register + 0x10 + 0x20 + read-write + 0X00000000 + + + CTL + CTL + 0 + 2 + + + TPRI + TPRI + 2 + 9 + + + INITCOUNT + INITCOUNT + 11 + 5 + + + + + ABFSR + ABFSR + Auxiliary Bus Fault Status + register + 0x18 + 0x20 + read-write + 0X00000000 + + + ITCM + ITCM + 0 + 1 + + + DTCM + DTCM + 1 + 1 + + + AHBP + AHBP + 2 + 1 + + + AXIM + AXIM + 3 + 1 + + + EPPB + EPPB + 4 + 1 + + + AXIMTYPE + AXIMTYPE + 8 + 2 + + + + + + + diff --git a/dev/svd/STM32F7x6.svd b/dev/svd/STM32F7x6.svd new file mode 100644 index 00000000000..b1861ca89d6 --- /dev/null +++ b/dev/svd/STM32F7x6.svd @@ -0,0 +1,70681 @@ + + + STM32F7x6 + 1.3 + STM32F7x6 + + + CM7 + r0p0 + little + false + false + 3 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + RNG + Random number generator + RNG + 0x50060800 + + 0x0 + 0x400 + registers + + + HASH_RNG + Hash and Rng global interrupt + 80 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + IE + Interrupt enable + 3 + 1 + + + RNGEN + Random number generator + enable + 2 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + 0x00000000 + + + SEIS + Seed error interrupt + status + 6 + 1 + read-write + + + CEIS + Clock error interrupt + status + 5 + 1 + read-write + + + SECS + Seed error current status + 2 + 1 + read-only + + + CECS + Clock error current status + 1 + 1 + read-only + + + DRDY + Data ready + 0 + 1 + read-only + + + + + DR + DR + data register + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data + 0 + 32 + + + + + + + HASH + Hash processor + HASH + 0x50060400 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + INIT + Initialize message digest + calculation + 2 + 1 + write-only + + + DMAE + DMA enable + 3 + 1 + read-write + + + DATATYPE + Data type selection + 4 + 2 + read-write + + + MODE + Mode selection + 6 + 1 + read-write + + + ALGO0 + Algorithm selection + 7 + 1 + read-write + + + NBW + Number of words already + pushed + 8 + 4 + read-only + + + DINNE + DIN not empty + 12 + 1 + read-only + + + MDMAT + Multiple DMA Transfers + 13 + 1 + read-write + + + LKEY + Long key selection + 16 + 1 + read-write + + + ALGO1 + ALGO + 18 + 1 + read-write + + + + + DIN + DIN + data input register + 0x4 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + STR + STR + start register + 0x8 + 0x20 + 0x00000000 + + + DCAL + Digest calculation + 8 + 1 + write-only + + + NBLW + Number of valid bits in the last word of + the message + 0 + 5 + read-write + + + + + HR0 + HR0 + digest registers + 0xC + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HR1 + HR1 + digest registers + 0x10 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HR2 + HR2 + digest registers + 0x14 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HR3 + HR3 + digest registers + 0x18 + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HR4 + HR4 + digest registers + 0x1C + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + IMR + IMR + interrupt enable register + 0x20 + 0x20 + read-write + 0x00000000 + + + DCIE + Digest calculation completion interrupt + enable + 1 + 1 + + + DINIE + Data input interrupt + enable + 0 + 1 + + + + + SR + SR + status register + 0x24 + 0x20 + 0x00000001 + + + BUSY + Busy bit + 3 + 1 + read-only + + + DMAS + DMA Status + 2 + 1 + read-only + + + DCIS + Digest calculation completion interrupt + status + 1 + 1 + read-write + + + DINIS + Data input interrupt + status + 0 + 1 + read-write + + + + + CSR0 + CSR0 + context swap registers + 0xF8 + 0x20 + read-write + 0x00000000 + + + CSR0 + CSR0 + 0 + 32 + + + + + CSR1 + CSR1 + context swap registers + 0xFC + 0x20 + read-write + 0x00000000 + + + CSR1 + CSR1 + 0 + 32 + + + + + CSR2 + CSR2 + context swap registers + 0x100 + 0x20 + read-write + 0x00000000 + + + CSR2 + CSR2 + 0 + 32 + + + + + CSR3 + CSR3 + context swap registers + 0x104 + 0x20 + read-write + 0x00000000 + + + CSR3 + CSR3 + 0 + 32 + + + + + CSR4 + CSR4 + context swap registers + 0x108 + 0x20 + read-write + 0x00000000 + + + CSR4 + CSR4 + 0 + 32 + + + + + CSR5 + CSR5 + context swap registers + 0x10C + 0x20 + read-write + 0x00000000 + + + CSR5 + CSR5 + 0 + 32 + + + + + CSR6 + CSR6 + context swap registers + 0x110 + 0x20 + read-write + 0x00000000 + + + CSR6 + CSR6 + 0 + 32 + + + + + CSR7 + CSR7 + context swap registers + 0x114 + 0x20 + read-write + 0x00000000 + + + CSR7 + CSR7 + 0 + 32 + + + + + CSR8 + CSR8 + context swap registers + 0x118 + 0x20 + read-write + 0x00000000 + + + CSR8 + CSR8 + 0 + 32 + + + + + CSR9 + CSR9 + context swap registers + 0x11C + 0x20 + read-write + 0x00000000 + + + CSR9 + CSR9 + 0 + 32 + + + + + CSR10 + CSR10 + context swap registers + 0x120 + 0x20 + read-write + 0x00000000 + + + CSR10 + CSR10 + 0 + 32 + + + + + CSR11 + CSR11 + context swap registers + 0x124 + 0x20 + read-write + 0x00000000 + + + CSR11 + CSR11 + 0 + 32 + + + + + CSR12 + CSR12 + context swap registers + 0x128 + 0x20 + read-write + 0x00000000 + + + CSR12 + CSR12 + 0 + 32 + + + + + CSR13 + CSR13 + context swap registers + 0x12C + 0x20 + read-write + 0x00000000 + + + CSR13 + CSR13 + 0 + 32 + + + + + CSR14 + CSR14 + context swap registers + 0x130 + 0x20 + read-write + 0x00000000 + + + CSR14 + CSR14 + 0 + 32 + + + + + CSR15 + CSR15 + context swap registers + 0x134 + 0x20 + read-write + 0x00000000 + + + CSR15 + CSR15 + 0 + 32 + + + + + CSR16 + CSR16 + context swap registers + 0x138 + 0x20 + read-write + 0x00000000 + + + CSR16 + CSR16 + 0 + 32 + + + + + CSR17 + CSR17 + context swap registers + 0x13C + 0x20 + read-write + 0x00000000 + + + CSR17 + CSR17 + 0 + 32 + + + + + CSR18 + CSR18 + context swap registers + 0x140 + 0x20 + read-write + 0x00000000 + + + CSR18 + CSR18 + 0 + 32 + + + + + CSR19 + CSR19 + context swap registers + 0x144 + 0x20 + read-write + 0x00000000 + + + CSR19 + CSR19 + 0 + 32 + + + + + CSR20 + CSR20 + context swap registers + 0x148 + 0x20 + read-write + 0x00000000 + + + CSR20 + CSR20 + 0 + 32 + + + + + CSR21 + CSR21 + context swap registers + 0x14C + 0x20 + read-write + 0x00000000 + + + CSR21 + CSR21 + 0 + 32 + + + + + CSR22 + CSR22 + context swap registers + 0x150 + 0x20 + read-write + 0x00000000 + + + CSR22 + CSR22 + 0 + 32 + + + + + CSR23 + CSR23 + context swap registers + 0x154 + 0x20 + read-write + 0x00000000 + + + CSR23 + CSR23 + 0 + 32 + + + + + CSR24 + CSR24 + context swap registers + 0x158 + 0x20 + read-write + 0x00000000 + + + CSR24 + CSR24 + 0 + 32 + + + + + CSR25 + CSR25 + context swap registers + 0x15C + 0x20 + read-write + 0x00000000 + + + CSR25 + CSR25 + 0 + 32 + + + + + CSR26 + CSR26 + context swap registers + 0x160 + 0x20 + read-write + 0x00000000 + + + CSR26 + CSR26 + 0 + 32 + + + + + CSR27 + CSR27 + context swap registers + 0x164 + 0x20 + read-write + 0x00000000 + + + CSR27 + CSR27 + 0 + 32 + + + + + CSR28 + CSR28 + context swap registers + 0x168 + 0x20 + read-write + 0x00000000 + + + CSR28 + CSR28 + 0 + 32 + + + + + CSR29 + CSR29 + context swap registers + 0x16C + 0x20 + read-write + 0x00000000 + + + CSR29 + CSR29 + 0 + 32 + + + + + CSR30 + CSR30 + context swap registers + 0x170 + 0x20 + read-write + 0x00000000 + + + CSR30 + CSR30 + 0 + 32 + + + + + CSR31 + CSR31 + context swap registers + 0x174 + 0x20 + read-write + 0x00000000 + + + CSR31 + CSR31 + 0 + 32 + + + + + CSR32 + CSR32 + context swap registers + 0x178 + 0x20 + read-write + 0x00000000 + + + CSR32 + CSR32 + 0 + 32 + + + + + CSR33 + CSR33 + context swap registers + 0x17C + 0x20 + read-write + 0x00000000 + + + CSR33 + CSR33 + 0 + 32 + + + + + CSR34 + CSR34 + context swap registers + 0x180 + 0x20 + read-write + 0x00000000 + + + CSR34 + CSR34 + 0 + 32 + + + + + CSR35 + CSR35 + context swap registers + 0x184 + 0x20 + read-write + 0x00000000 + + + CSR35 + CSR35 + 0 + 32 + + + + + CSR36 + CSR36 + context swap registers + 0x188 + 0x20 + read-write + 0x00000000 + + + CSR36 + CSR36 + 0 + 32 + + + + + CSR37 + CSR37 + context swap registers + 0x18C + 0x20 + read-write + 0x00000000 + + + CSR37 + CSR37 + 0 + 32 + + + + + CSR38 + CSR38 + context swap registers + 0x190 + 0x20 + read-write + 0x00000000 + + + CSR38 + CSR38 + 0 + 32 + + + + + CSR39 + CSR39 + context swap registers + 0x194 + 0x20 + read-write + 0x00000000 + + + CSR39 + CSR39 + 0 + 32 + + + + + CSR40 + CSR40 + context swap registers + 0x198 + 0x20 + read-write + 0x00000000 + + + CSR40 + CSR40 + 0 + 32 + + + + + CSR41 + CSR41 + context swap registers + 0x19C + 0x20 + read-write + 0x00000000 + + + CSR41 + CSR41 + 0 + 32 + + + + + CSR42 + CSR42 + context swap registers + 0x1A0 + 0x20 + read-write + 0x00000000 + + + CSR42 + CSR42 + 0 + 32 + + + + + CSR43 + CSR43 + context swap registers + 0x1A4 + 0x20 + read-write + 0x00000000 + + + CSR43 + CSR43 + 0 + 32 + + + + + CSR44 + CSR44 + context swap registers + 0x1A8 + 0x20 + read-write + 0x00000000 + + + CSR44 + CSR44 + 0 + 32 + + + + + CSR45 + CSR45 + context swap registers + 0x1AC + 0x20 + read-write + 0x00000000 + + + CSR45 + CSR45 + 0 + 32 + + + + + CSR46 + CSR46 + context swap registers + 0x1B0 + 0x20 + read-write + 0x00000000 + + + CSR46 + CSR46 + 0 + 32 + + + + + CSR47 + CSR47 + context swap registers + 0x1B4 + 0x20 + read-write + 0x00000000 + + + CSR47 + CSR47 + 0 + 32 + + + + + CSR48 + CSR48 + context swap registers + 0x1B8 + 0x20 + read-write + 0x00000000 + + + CSR48 + CSR48 + 0 + 32 + + + + + CSR49 + CSR49 + context swap registers + 0x1BC + 0x20 + read-write + 0x00000000 + + + CSR49 + CSR49 + 0 + 32 + + + + + CSR50 + CSR50 + context swap registers + 0x1C0 + 0x20 + read-write + 0x00000000 + + + CSR50 + CSR50 + 0 + 32 + + + + + CSR51 + CSR51 + context swap registers + 0x1C4 + 0x20 + read-write + 0x00000000 + + + CSR51 + CSR51 + 0 + 32 + + + + + CSR52 + CSR52 + context swap registers + 0x1C8 + 0x20 + read-write + 0x00000000 + + + CSR52 + CSR52 + 0 + 32 + + + + + CSR53 + CSR53 + context swap registers + 0x1CC + 0x20 + read-write + 0x00000000 + + + CSR53 + CSR53 + 0 + 32 + + + + + HASH_HR0 + HASH_HR0 + HASH digest register + 0x310 + 0x20 + read-only + 0x00000000 + + + H0 + H0 + 0 + 32 + + + + + HASH_HR1 + HASH_HR1 + read-only + 0x314 + 0x20 + read-only + 0x00000000 + + + H1 + H1 + 0 + 32 + + + + + HASH_HR2 + HASH_HR2 + read-only + 0x318 + 0x20 + read-only + 0x00000000 + + + H2 + H2 + 0 + 32 + + + + + HASH_HR3 + HASH_HR3 + read-only + 0x31C + 0x20 + read-only + 0x00000000 + + + H3 + H3 + 0 + 32 + + + + + HASH_HR4 + HASH_HR4 + read-only + 0x320 + 0x20 + read-only + 0x00000000 + + + H4 + H4 + 0 + 32 + + + + + HASH_HR5 + HASH_HR5 + read-only + 0x324 + 0x20 + read-only + 0x00000000 + + + H5 + H5 + 0 + 32 + + + + + HASH_HR6 + HASH_HR6 + read-only + 0x328 + 0x20 + read-only + 0x00000000 + + + H6 + H6 + 0 + 32 + + + + + HASH_HR7 + HASH_HR7 + read-only + 0x32C + 0x20 + read-only + 0x00000000 + + + H7 + H7 + 0 + 32 + + + + + + + CRYP + Cryptographic processor + CRYP + 0x50060000 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + 0x00000000 + + + ALGODIR + Algorithm direction + 2 + 1 + read-write + + + ALGOMODE0 + Algorithm mode + 3 + 3 + read-write + + + DATATYPE + Data type selection + 6 + 2 + read-write + + + KEYSIZE + Key size selection (AES mode + only) + 8 + 2 + read-write + + + FFLUSH + FIFO flush + 14 + 1 + write-only + + + CRYPEN + Cryptographic processor + enable + 15 + 1 + read-write + + + GCM_CCMPH + GCM_CCMPH + 16 + 2 + read-write + + + ALGOMODE3 + ALGOMODE + 19 + 1 + read-write + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x00000003 + + + BUSY + Busy bit + 4 + 1 + + + OFFU + Output FIFO full + 3 + 1 + + + OFNE + Output FIFO not empty + 2 + 1 + + + IFNF + Input FIFO not full + 1 + 1 + + + IFEM + Input FIFO empty + 0 + 1 + + + + + DIN + DIN + data input register + 0x8 + 0x20 + read-write + 0x00000000 + + + DATAIN + Data input + 0 + 32 + + + + + DOUT + DOUT + data output register + 0xC + 0x20 + read-only + 0x00000000 + + + DATAOUT + Data output + 0 + 32 + + + + + DMACR + DMACR + DMA control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DOEN + DMA output enable + 1 + 1 + + + DIEN + DMA input enable + 0 + 1 + + + + + IMSCR + IMSCR + interrupt mask set/clear + register + 0x14 + 0x20 + read-write + 0x00000000 + + + OUTIM + Output FIFO service interrupt + mask + 1 + 1 + + + INIM + Input FIFO service interrupt + mask + 0 + 1 + + + + + RISR + RISR + raw interrupt status register + 0x18 + 0x20 + read-only + 0x00000001 + + + OUTRIS + Output FIFO service raw interrupt + status + 1 + 1 + + + INRIS + Input FIFO service raw interrupt + status + 0 + 1 + + + + + MISR + MISR + masked interrupt status + register + 0x1C + 0x20 + read-only + 0x00000000 + + + OUTMIS + Output FIFO service masked interrupt + status + 1 + 1 + + + INMIS + Input FIFO service masked interrupt + status + 0 + 1 + + + + + K0LR + K0LR + key registers + 0x20 + 0x20 + write-only + 0x00000000 + + + b224 + b224 + 0 + 1 + + + b225 + b225 + 1 + 1 + + + b226 + b226 + 2 + 1 + + + b227 + b227 + 3 + 1 + + + b228 + b228 + 4 + 1 + + + b229 + b229 + 5 + 1 + + + b230 + b230 + 6 + 1 + + + b231 + b231 + 7 + 1 + + + b232 + b232 + 8 + 1 + + + b233 + b233 + 9 + 1 + + + b234 + b234 + 10 + 1 + + + b235 + b235 + 11 + 1 + + + b236 + b236 + 12 + 1 + + + b237 + b237 + 13 + 1 + + + b238 + b238 + 14 + 1 + + + b239 + b239 + 15 + 1 + + + b240 + b240 + 16 + 1 + + + b241 + b241 + 17 + 1 + + + b242 + b242 + 18 + 1 + + + b243 + b243 + 19 + 1 + + + b244 + b244 + 20 + 1 + + + b245 + b245 + 21 + 1 + + + b246 + b246 + 22 + 1 + + + b247 + b247 + 23 + 1 + + + b248 + b248 + 24 + 1 + + + b249 + b249 + 25 + 1 + + + b250 + b250 + 26 + 1 + + + b251 + b251 + 27 + 1 + + + b252 + b252 + 28 + 1 + + + b253 + b253 + 29 + 1 + + + b254 + b254 + 30 + 1 + + + b255 + b255 + 31 + 1 + + + + + K0RR + K0RR + key registers + 0x24 + 0x20 + write-only + 0x00000000 + + + b192 + b192 + 0 + 1 + + + b193 + b193 + 1 + 1 + + + b194 + b194 + 2 + 1 + + + b195 + b195 + 3 + 1 + + + b196 + b196 + 4 + 1 + + + b197 + b197 + 5 + 1 + + + b198 + b198 + 6 + 1 + + + b199 + b199 + 7 + 1 + + + b200 + b200 + 8 + 1 + + + b201 + b201 + 9 + 1 + + + b202 + b202 + 10 + 1 + + + b203 + b203 + 11 + 1 + + + b204 + b204 + 12 + 1 + + + b205 + b205 + 13 + 1 + + + b206 + b206 + 14 + 1 + + + b207 + b207 + 15 + 1 + + + b208 + b208 + 16 + 1 + + + b209 + b209 + 17 + 1 + + + b210 + b210 + 18 + 1 + + + b211 + b211 + 19 + 1 + + + b212 + b212 + 20 + 1 + + + b213 + b213 + 21 + 1 + + + b214 + b214 + 22 + 1 + + + b215 + b215 + 23 + 1 + + + b216 + b216 + 24 + 1 + + + b217 + b217 + 25 + 1 + + + b218 + b218 + 26 + 1 + + + b219 + b219 + 27 + 1 + + + b220 + b220 + 28 + 1 + + + b221 + b221 + 29 + 1 + + + b222 + b222 + 30 + 1 + + + b223 + b223 + 31 + 1 + + + + + K1LR + K1LR + key registers + 0x28 + 0x20 + write-only + 0x00000000 + + + b160 + b160 + 0 + 1 + + + b161 + b161 + 1 + 1 + + + b162 + b162 + 2 + 1 + + + b163 + b163 + 3 + 1 + + + b164 + b164 + 4 + 1 + + + b165 + b165 + 5 + 1 + + + b166 + b166 + 6 + 1 + + + b167 + b167 + 7 + 1 + + + b168 + b168 + 8 + 1 + + + b169 + b169 + 9 + 1 + + + b170 + b170 + 10 + 1 + + + b171 + b171 + 11 + 1 + + + b172 + b172 + 12 + 1 + + + b173 + b173 + 13 + 1 + + + b174 + b174 + 14 + 1 + + + b175 + b175 + 15 + 1 + + + b176 + b176 + 16 + 1 + + + b177 + b177 + 17 + 1 + + + b178 + b178 + 18 + 1 + + + b179 + b179 + 19 + 1 + + + b180 + b180 + 20 + 1 + + + b181 + b181 + 21 + 1 + + + b182 + b182 + 22 + 1 + + + b183 + b183 + 23 + 1 + + + b184 + b184 + 24 + 1 + + + b185 + b185 + 25 + 1 + + + b186 + b186 + 26 + 1 + + + b187 + b187 + 27 + 1 + + + b188 + b188 + 28 + 1 + + + b189 + b189 + 29 + 1 + + + b190 + b190 + 30 + 1 + + + b191 + b191 + 31 + 1 + + + + + K1RR + K1RR + key registers + 0x2C + 0x20 + write-only + 0x00000000 + + + b128 + b128 + 0 + 1 + + + b129 + b129 + 1 + 1 + + + b130 + b130 + 2 + 1 + + + b131 + b131 + 3 + 1 + + + b132 + b132 + 4 + 1 + + + b133 + b133 + 5 + 1 + + + b134 + b134 + 6 + 1 + + + b135 + b135 + 7 + 1 + + + b136 + b136 + 8 + 1 + + + b137 + b137 + 9 + 1 + + + b138 + b138 + 10 + 1 + + + b139 + b139 + 11 + 1 + + + b140 + b140 + 12 + 1 + + + b141 + b141 + 13 + 1 + + + b142 + b142 + 14 + 1 + + + b143 + b143 + 15 + 1 + + + b144 + b144 + 16 + 1 + + + b145 + b145 + 17 + 1 + + + b146 + b146 + 18 + 1 + + + b147 + b147 + 19 + 1 + + + b148 + b148 + 20 + 1 + + + b149 + b149 + 21 + 1 + + + b150 + b150 + 22 + 1 + + + b151 + b151 + 23 + 1 + + + b152 + b152 + 24 + 1 + + + b153 + b153 + 25 + 1 + + + b154 + b154 + 26 + 1 + + + b155 + b155 + 27 + 1 + + + b156 + b156 + 28 + 1 + + + b157 + b157 + 29 + 1 + + + b158 + b158 + 30 + 1 + + + b159 + b159 + 31 + 1 + + + + + K2LR + K2LR + key registers + 0x30 + 0x20 + write-only + 0x00000000 + + + b96 + b96 + 0 + 1 + + + b97 + b97 + 1 + 1 + + + b98 + b98 + 2 + 1 + + + b99 + b99 + 3 + 1 + + + b100 + b100 + 4 + 1 + + + b101 + b101 + 5 + 1 + + + b102 + b102 + 6 + 1 + + + b103 + b103 + 7 + 1 + + + b104 + b104 + 8 + 1 + + + b105 + b105 + 9 + 1 + + + b106 + b106 + 10 + 1 + + + b107 + b107 + 11 + 1 + + + b108 + b108 + 12 + 1 + + + b109 + b109 + 13 + 1 + + + b110 + b110 + 14 + 1 + + + b111 + b111 + 15 + 1 + + + b112 + b112 + 16 + 1 + + + b113 + b113 + 17 + 1 + + + b114 + b114 + 18 + 1 + + + b115 + b115 + 19 + 1 + + + b116 + b116 + 20 + 1 + + + b117 + b117 + 21 + 1 + + + b118 + b118 + 22 + 1 + + + b119 + b119 + 23 + 1 + + + b120 + b120 + 24 + 1 + + + b121 + b121 + 25 + 1 + + + b122 + b122 + 26 + 1 + + + b123 + b123 + 27 + 1 + + + b124 + b124 + 28 + 1 + + + b125 + b125 + 29 + 1 + + + b126 + b126 + 30 + 1 + + + b127 + b127 + 31 + 1 + + + + + K2RR + K2RR + key registers + 0x34 + 0x20 + write-only + 0x00000000 + + + b64 + b64 + 0 + 1 + + + b65 + b65 + 1 + 1 + + + b66 + b66 + 2 + 1 + + + b67 + b67 + 3 + 1 + + + b68 + b68 + 4 + 1 + + + b69 + b69 + 5 + 1 + + + b70 + b70 + 6 + 1 + + + b71 + b71 + 7 + 1 + + + b72 + b72 + 8 + 1 + + + b73 + b73 + 9 + 1 + + + b74 + b74 + 10 + 1 + + + b75 + b75 + 11 + 1 + + + b76 + b76 + 12 + 1 + + + b77 + b77 + 13 + 1 + + + b78 + b78 + 14 + 1 + + + b79 + b79 + 15 + 1 + + + b80 + b80 + 16 + 1 + + + b81 + b81 + 17 + 1 + + + b82 + b82 + 18 + 1 + + + b83 + b83 + 19 + 1 + + + b84 + b84 + 20 + 1 + + + b85 + b85 + 21 + 1 + + + b86 + b86 + 22 + 1 + + + b87 + b87 + 23 + 1 + + + b88 + b88 + 24 + 1 + + + b89 + b89 + 25 + 1 + + + b90 + b90 + 26 + 1 + + + b91 + b91 + 27 + 1 + + + b92 + b92 + 28 + 1 + + + b93 + b93 + 29 + 1 + + + b94 + b94 + 30 + 1 + + + b95 + b95 + 31 + 1 + + + + + K3LR + K3LR + key registers + 0x38 + 0x20 + write-only + 0x00000000 + + + b32 + b32 + 0 + 1 + + + b33 + b33 + 1 + 1 + + + b34 + b34 + 2 + 1 + + + b35 + b35 + 3 + 1 + + + b36 + b36 + 4 + 1 + + + b37 + b37 + 5 + 1 + + + b38 + b38 + 6 + 1 + + + b39 + b39 + 7 + 1 + + + b40 + b40 + 8 + 1 + + + b41 + b41 + 9 + 1 + + + b42 + b42 + 10 + 1 + + + b43 + b43 + 11 + 1 + + + b44 + b44 + 12 + 1 + + + b45 + b45 + 13 + 1 + + + b46 + b46 + 14 + 1 + + + b47 + b47 + 15 + 1 + + + b48 + b48 + 16 + 1 + + + b49 + b49 + 17 + 1 + + + b50 + b50 + 18 + 1 + + + b51 + b51 + 19 + 1 + + + b52 + b52 + 20 + 1 + + + b53 + b53 + 21 + 1 + + + b54 + b54 + 22 + 1 + + + b55 + b55 + 23 + 1 + + + b56 + b56 + 24 + 1 + + + b57 + b57 + 25 + 1 + + + b58 + b58 + 26 + 1 + + + b59 + b59 + 27 + 1 + + + b60 + b60 + 28 + 1 + + + b61 + b61 + 29 + 1 + + + b62 + b62 + 30 + 1 + + + b63 + b63 + 31 + 1 + + + + + K3RR + K3RR + key registers + 0x3C + 0x20 + write-only + 0x00000000 + + + b0 + b0 + 0 + 1 + + + b1 + b1 + 1 + 1 + + + b2 + b2 + 2 + 1 + + + b3 + b3 + 3 + 1 + + + b4 + b4 + 4 + 1 + + + b5 + b5 + 5 + 1 + + + b6 + b6 + 6 + 1 + + + b7 + b7 + 7 + 1 + + + b8 + b8 + 8 + 1 + + + b9 + b9 + 9 + 1 + + + b10 + b10 + 10 + 1 + + + b11 + b11 + 11 + 1 + + + b12 + b12 + 12 + 1 + + + b13 + b13 + 13 + 1 + + + b14 + b14 + 14 + 1 + + + b15 + b15 + 15 + 1 + + + b16 + b16 + 16 + 1 + + + b17 + b17 + 17 + 1 + + + b18 + b18 + 18 + 1 + + + b19 + b19 + 19 + 1 + + + b20 + b20 + 20 + 1 + + + b21 + b21 + 21 + 1 + + + b22 + b22 + 22 + 1 + + + b23 + b23 + 23 + 1 + + + b24 + b24 + 24 + 1 + + + b25 + b25 + 25 + 1 + + + b26 + b26 + 26 + 1 + + + b27 + b27 + 27 + 1 + + + b28 + b28 + 28 + 1 + + + b29 + b29 + 29 + 1 + + + b30 + b30 + 30 + 1 + + + b31 + b31 + 31 + 1 + + + + + IV0LR + IV0LR + initialization vector + registers + 0x40 + 0x20 + read-write + 0x00000000 + + + IV31 + IV31 + 0 + 1 + + + IV30 + IV30 + 1 + 1 + + + IV29 + IV29 + 2 + 1 + + + IV28 + IV28 + 3 + 1 + + + IV27 + IV27 + 4 + 1 + + + IV26 + IV26 + 5 + 1 + + + IV25 + IV25 + 6 + 1 + + + IV24 + IV24 + 7 + 1 + + + IV23 + IV23 + 8 + 1 + + + IV22 + IV22 + 9 + 1 + + + IV21 + IV21 + 10 + 1 + + + IV20 + IV20 + 11 + 1 + + + IV19 + IV19 + 12 + 1 + + + IV18 + IV18 + 13 + 1 + + + IV17 + IV17 + 14 + 1 + + + IV16 + IV16 + 15 + 1 + + + IV15 + IV15 + 16 + 1 + + + IV14 + IV14 + 17 + 1 + + + IV13 + IV13 + 18 + 1 + + + IV12 + IV12 + 19 + 1 + + + IV11 + IV11 + 20 + 1 + + + IV10 + IV10 + 21 + 1 + + + IV9 + IV9 + 22 + 1 + + + IV8 + IV8 + 23 + 1 + + + IV7 + IV7 + 24 + 1 + + + IV6 + IV6 + 25 + 1 + + + IV5 + IV5 + 26 + 1 + + + IV4 + IV4 + 27 + 1 + + + IV3 + IV3 + 28 + 1 + + + IV2 + IV2 + 29 + 1 + + + IV1 + IV1 + 30 + 1 + + + IV0 + IV0 + 31 + 1 + + + + + IV0RR + IV0RR + initialization vector + registers + 0x44 + 0x20 + read-write + 0x00000000 + + + IV63 + IV63 + 0 + 1 + + + IV62 + IV62 + 1 + 1 + + + IV61 + IV61 + 2 + 1 + + + IV60 + IV60 + 3 + 1 + + + IV59 + IV59 + 4 + 1 + + + IV58 + IV58 + 5 + 1 + + + IV57 + IV57 + 6 + 1 + + + IV56 + IV56 + 7 + 1 + + + IV55 + IV55 + 8 + 1 + + + IV54 + IV54 + 9 + 1 + + + IV53 + IV53 + 10 + 1 + + + IV52 + IV52 + 11 + 1 + + + IV51 + IV51 + 12 + 1 + + + IV50 + IV50 + 13 + 1 + + + IV49 + IV49 + 14 + 1 + + + IV48 + IV48 + 15 + 1 + + + IV47 + IV47 + 16 + 1 + + + IV46 + IV46 + 17 + 1 + + + IV45 + IV45 + 18 + 1 + + + IV44 + IV44 + 19 + 1 + + + IV43 + IV43 + 20 + 1 + + + IV42 + IV42 + 21 + 1 + + + IV41 + IV41 + 22 + 1 + + + IV40 + IV40 + 23 + 1 + + + IV39 + IV39 + 24 + 1 + + + IV38 + IV38 + 25 + 1 + + + IV37 + IV37 + 26 + 1 + + + IV36 + IV36 + 27 + 1 + + + IV35 + IV35 + 28 + 1 + + + IV34 + IV34 + 29 + 1 + + + IV33 + IV33 + 30 + 1 + + + IV32 + IV32 + 31 + 1 + + + + + IV1LR + IV1LR + initialization vector + registers + 0x48 + 0x20 + read-write + 0x00000000 + + + IV95 + IV95 + 0 + 1 + + + IV94 + IV94 + 1 + 1 + + + IV93 + IV93 + 2 + 1 + + + IV92 + IV92 + 3 + 1 + + + IV91 + IV91 + 4 + 1 + + + IV90 + IV90 + 5 + 1 + + + IV89 + IV89 + 6 + 1 + + + IV88 + IV88 + 7 + 1 + + + IV87 + IV87 + 8 + 1 + + + IV86 + IV86 + 9 + 1 + + + IV85 + IV85 + 10 + 1 + + + IV84 + IV84 + 11 + 1 + + + IV83 + IV83 + 12 + 1 + + + IV82 + IV82 + 13 + 1 + + + IV81 + IV81 + 14 + 1 + + + IV80 + IV80 + 15 + 1 + + + IV79 + IV79 + 16 + 1 + + + IV78 + IV78 + 17 + 1 + + + IV77 + IV77 + 18 + 1 + + + IV76 + IV76 + 19 + 1 + + + IV75 + IV75 + 20 + 1 + + + IV74 + IV74 + 21 + 1 + + + IV73 + IV73 + 22 + 1 + + + IV72 + IV72 + 23 + 1 + + + IV71 + IV71 + 24 + 1 + + + IV70 + IV70 + 25 + 1 + + + IV69 + IV69 + 26 + 1 + + + IV68 + IV68 + 27 + 1 + + + IV67 + IV67 + 28 + 1 + + + IV66 + IV66 + 29 + 1 + + + IV65 + IV65 + 30 + 1 + + + IV64 + IV64 + 31 + 1 + + + + + IV1RR + IV1RR + initialization vector + registers + 0x4C + 0x20 + read-write + 0x00000000 + + + IV127 + IV127 + 0 + 1 + + + IV126 + IV126 + 1 + 1 + + + IV125 + IV125 + 2 + 1 + + + IV124 + IV124 + 3 + 1 + + + IV123 + IV123 + 4 + 1 + + + IV122 + IV122 + 5 + 1 + + + IV121 + IV121 + 6 + 1 + + + IV120 + IV120 + 7 + 1 + + + IV119 + IV119 + 8 + 1 + + + IV118 + IV118 + 9 + 1 + + + IV117 + IV117 + 10 + 1 + + + IV116 + IV116 + 11 + 1 + + + IV115 + IV115 + 12 + 1 + + + IV114 + IV114 + 13 + 1 + + + IV113 + IV113 + 14 + 1 + + + IV112 + IV112 + 15 + 1 + + + IV111 + IV111 + 16 + 1 + + + IV110 + IV110 + 17 + 1 + + + IV109 + IV109 + 18 + 1 + + + IV108 + IV108 + 19 + 1 + + + IV107 + IV107 + 20 + 1 + + + IV106 + IV106 + 21 + 1 + + + IV105 + IV105 + 22 + 1 + + + IV104 + IV104 + 23 + 1 + + + IV103 + IV103 + 24 + 1 + + + IV102 + IV102 + 25 + 1 + + + IV101 + IV101 + 26 + 1 + + + IV100 + IV100 + 27 + 1 + + + IV99 + IV99 + 28 + 1 + + + IV98 + IV98 + 29 + 1 + + + IV97 + IV97 + 30 + 1 + + + IV96 + IV96 + 31 + 1 + + + + + CSGCMCCM0R + CSGCMCCM0R + context swap register + 0x50 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM0R + CSGCMCCM0R + 0 + 32 + + + + + CSGCMCCM1R + CSGCMCCM1R + context swap register + 0x54 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM1R + CSGCMCCM1R + 0 + 32 + + + + + CSGCMCCM2R + CSGCMCCM2R + context swap register + 0x58 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM2R + CSGCMCCM2R + 0 + 32 + + + + + CSGCMCCM3R + CSGCMCCM3R + context swap register + 0x5C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM3R + CSGCMCCM3R + 0 + 32 + + + + + CSGCMCCM4R + CSGCMCCM4R + context swap register + 0x60 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM4R + CSGCMCCM4R + 0 + 32 + + + + + CSGCMCCM5R + CSGCMCCM5R + context swap register + 0x64 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM5R + CSGCMCCM5R + 0 + 32 + + + + + CSGCMCCM6R + CSGCMCCM6R + context swap register + 0x68 + 0x20 + read-write + 0x00000000 + + + CSGCMCCM6R + CSGCMCCM6R + 0 + 32 + + + + + CSGCMCCM7R + CSGCMCCM7R + context swap register + 0x6C + 0x20 + read-write + 0x00000000 + + + CSGCMCCM7R + CSGCMCCM7R + 0 + 32 + + + + + CSGCM0R + CSGCM0R + context swap register + 0x70 + 0x20 + read-write + 0x00000000 + + + CSGCM0R + CSGCM0R + 0 + 32 + + + + + CSGCM1R + CSGCM1R + context swap register + 0x74 + 0x20 + read-write + 0x00000000 + + + CSGCM1R + CSGCM1R + 0 + 32 + + + + + CSGCM2R + CSGCM2R + context swap register + 0x78 + 0x20 + read-write + 0x00000000 + + + CSGCM2R + CSGCM2R + 0 + 32 + + + + + CSGCM3R + CSGCM3R + context swap register + 0x7C + 0x20 + read-write + 0x00000000 + + + CSGCM3R + CSGCM3R + 0 + 32 + + + + + CSGCM4R + CSGCM4R + context swap register + 0x80 + 0x20 + read-write + 0x00000000 + + + CSGCM4R + CSGCM4R + 0 + 32 + + + + + CSGCM5R + CSGCM5R + context swap register + 0x84 + 0x20 + read-write + 0x00000000 + + + CSGCM5R + CSGCM5R + 0 + 32 + + + + + CSGCM6R + CSGCM6R + context swap register + 0x88 + 0x20 + read-write + 0x00000000 + + + CSGCM6R + CSGCM6R + 0 + 32 + + + + + CSGCM7R + CSGCM7R + context swap register + 0x8C + 0x20 + read-write + 0x00000000 + + + CSGCM7R + CSGCM7R + 0 + 32 + + + + + + + DCMI + Digital camera interface + DCMI + 0x50050000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ENABLE + DCMI enable + 14 + 1 + + + EDM + Extended data mode + 10 + 2 + + + FCRC + Frame capture rate control + 8 + 2 + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + + + PCKPOL + Pixel clock polarity + 5 + 1 + + + ESS + Embedded synchronization + select + 4 + 1 + + + JPEG + JPEG format + 3 + 1 + + + CROP + Crop feature + 2 + 1 + + + CM + Capture mode + 1 + 1 + + + CAPTURE + Capture enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + FMC + Flexible memory controller + FSMC + 0xA0000000 + + 0x0 + 0x1000 + registers + + + FMC + FMC global interrupt + 48 + + + + BCR1 + BCR1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030D0 + + + CCLKEN + CCLKEN + 20 + 1 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR1 + BTR1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR2 + BCR2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR2 + BTR2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR3 + BCR3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR3 + BTR3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BCR4 + BCR4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D0 + + + CBURSTRW + CBURSTRW + 19 + 1 + + + ASYNCWAIT + ASYNCWAIT + 15 + 1 + + + EXTMOD + EXTMOD + 14 + 1 + + + WAITEN + WAITEN + 13 + 1 + + + WREN + WREN + 12 + 1 + + + WAITCFG + WAITCFG + 11 + 1 + + + WRAPMOD + WRAPMOD + 10 + 1 + + + WAITPOL + WAITPOL + 9 + 1 + + + BURSTEN + BURSTEN + 8 + 1 + + + FACCEN + FACCEN + 6 + 1 + + + MWID + MWID + 4 + 2 + + + MTYP + MTYP + 2 + 2 + + + MUXEN + MUXEN + 1 + 1 + + + MBKEN + MBKEN + 0 + 1 + + + + + BTR4 + BTR4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0xFFFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + BUSTURN + BUSTURN + 16 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + PCR + PCR + PC Card/NAND Flash control + register + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPS + ECCPS + 17 + 3 + + + TAR + TAR + 13 + 4 + + + TCLR + TCLR + 9 + 4 + + + ECCEN + ECCEN + 6 + 1 + + + PWID + PWID + 4 + 2 + + + PTYP + PTYP + 3 + 1 + + + PBKEN + PBKEN + 2 + 1 + + + PWAITEN + PWAITEN + 1 + 1 + + + + + SR + SR + FIFO status and interrupt + register + 0x84 + 0x20 + 0x00000040 + + + FEMPT + FEMPT + 6 + 1 + read-only + + + IFEN + IFEN + 5 + 1 + read-write + + + ILEN + ILEN + 4 + 1 + read-write + + + IREN + IREN + 3 + 1 + read-write + + + IFS + IFS + 2 + 1 + read-write + + + ILS + ILS + 1 + 1 + read-write + + + IRS + IRS + 0 + 1 + read-write + + + + + PMEM + PMEM + Common memory space timing + register + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMHIZx + MEMHIZx + 24 + 8 + + + MEMHOLDx + MEMHOLDx + 16 + 8 + + + MEMWAITx + MEMWAITx + 8 + 8 + + + MEMSETx + MEMSETx + 0 + 8 + + + + + PATT + PATT + Attribute memory space timing + register + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTHIZx + ATTHIZx + 24 + 8 + + + ATTHOLDx + ATTHOLDx + 16 + 8 + + + ATTWAITx + ATTWAITx + 8 + 8 + + + ATTSETx + ATTSETx + 0 + 8 + + + + + ECCR + ECCR + ECC result register + 0x94 + 0x20 + read-only + 0x00000000 + + + ECCx + ECCx + 0 + 32 + + + + + BWTR1 + BWTR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR2 + BWTR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR3 + BWTR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + BWTR4 + BWTR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ACCMOD + ACCMOD + 28 + 2 + + + DATLAT + DATLAT + 24 + 4 + + + CLKDIV + CLKDIV + 20 + 4 + + + DATAST + DATAST + 8 + 8 + + + ADDHLD + ADDHLD + 4 + 4 + + + ADDSET + ADDSET + 0 + 4 + + + + + SDCR1 + SDCR1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDCR2 + SDCR2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address + bits + 0 + 2 + + + NR + Number of row address bits + 2 + 2 + + + MWID + Memory data bus width + 4 + 2 + + + NB + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WP + Write protection + 9 + 1 + + + SDCLK + SDRAM clock configuration + 10 + 2 + + + RBURST + Burst read + 12 + 1 + + + RPIPE + Read pipe + 13 + 2 + + + + + SDTR1 + SDTR1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDTR2 + SDTR2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to + Active + 0 + 4 + + + TXSR + Exit self-refresh delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Row cycle delay + 12 + 4 + + + TWR + Recovery delay + 16 + 4 + + + TRP + Row precharge delay + 20 + 4 + + + TRCD + Row to column delay + 24 + 4 + + + + + SDCMR + SDCMR + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + MODE + Command mode + 0 + 3 + write-only + + + CTB2 + Command target bank 2 + 3 + 1 + write-only + + + CTB1 + Command target bank 1 + 4 + 1 + write-only + + + NRFS + Number of Auto-refresh + 5 + 4 + read-write + + + MRD + Mode Register definition + 9 + 13 + read-write + + + + + SDRTR + SDRTR + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag + 0 + 1 + write-only + + + COUNT + Refresh Timer Count + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + RE + Refresh error flag + 0 + 1 + + + MODES1 + Status Mode for Bank 1 + 1 + 2 + + + MODES2 + Status Mode for Bank 2 + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + + + DBG + Debug support + DBG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + DBGMCU_IDCODE + DBGMCU_IDCODE + IDCODE + 0x0 + 0x20 + read-only + 0x10006411 + + + DEV_ID + DEV_ID + 0 + 12 + + + REV_ID + REV_ID + 16 + 16 + + + + + DBGMCU_CR + DBGMCU_CR + Control Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBG_SLEEP + DBG_SLEEP + 0 + 1 + + + DBG_STOP + DBG_STOP + 1 + 1 + + + DBG_STANDBY + DBG_STANDBY + 2 + 1 + + + TRACE_IOEN + TRACE_IOEN + 5 + 1 + + + TRACE_MODE + TRACE_MODE + 6 + 2 + + + + + DBGMCU_APB1_FZ + DBGMCU_APB1_FZ + Debug MCU APB1 Freeze registe + 0x8 + 0x20 + read-write + 0x00000000 + + + DBG_TIM2_STOP + DBG_TIM2_STOP + 0 + 1 + + + DBG_TIM3_STOP + DBG_TIM3 _STOP + 1 + 1 + + + DBG_TIM4_STOP + DBG_TIM4_STOP + 2 + 1 + + + DBG_TIM5_STOP + DBG_TIM5_STOP + 3 + 1 + + + DBG_TIM6_STOP + DBG_TIM6_STOP + 4 + 1 + + + DBG_TIM7_STOP + DBG_TIM7_STOP + 5 + 1 + + + DBG_TIM12_STOP + DBG_TIM12_STOP + 6 + 1 + + + DBG_TIM13_STOP + DBG_TIM13_STOP + 7 + 1 + + + DBG_TIM14_STOP + DBG_TIM14_STOP + 8 + 1 + + + DBG_WWDG_STOP + DBG_WWDG_STOP + 11 + 1 + + + DBG_IWDEG_STOP + DBG_IWDEG_STOP + 12 + 1 + + + DBG_J2C1_SMBUS_TIMEOUT + DBG_J2C1_SMBUS_TIMEOUT + 21 + 1 + + + DBG_J2C2_SMBUS_TIMEOUT + DBG_J2C2_SMBUS_TIMEOUT + 22 + 1 + + + DBG_J2C3SMBUS_TIMEOUT + DBG_J2C3SMBUS_TIMEOUT + 23 + 1 + + + DBG_CAN1_STOP + DBG_CAN1_STOP + 25 + 1 + + + DBG_CAN2_STOP + DBG_CAN2_STOP + 26 + 1 + + + + + DBGMCU_APB2_FZ + DBGMCU_APB2_FZ + Debug MCU APB2 Freeze registe + 0xC + 0x20 + read-write + 0x00000000 + + + DBG_TIM1_STOP + TIM1 counter stopped when core is + halted + 0 + 1 + + + DBG_TIM8_STOP + TIM8 counter stopped when core is + halted + 1 + 1 + + + DBG_TIM9_STOP + TIM9 counter stopped when core is + halted + 16 + 1 + + + DBG_TIM10_STOP + TIM10 counter stopped when core is + halted + 17 + 1 + + + DBG_TIM11_STOP + TIM11 counter stopped when core is + halted + 18 + 1 + + + + + + + DMA2 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x400 + registers + + + DMA2_Stream0 + DMA2 Stream0 global interrupt + 56 + + + DMA2_Stream1 + DMA2 Stream1 global interrupt + 57 + + + DMA2_Stream2 + DMA2 Stream2 global interrupt + 58 + + + DMA2_Stream3 + DMA2 Stream3 global interrupt + 59 + + + DMA2_Stream4 + DMA2 Stream4 global interrupt + 60 + + + DMA2_Stream5 + DMA2 Stream5 global interrupt + 68 + + + DMA2_Stream6 + DMA2 Stream6 global interrupt + 69 + + + DMA2_Stream7 + DMA2 Stream7 global interrupt + 70 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + CHSEL + Channel selection + 25 + 3 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA1 + 0x40026000 + + DMA1_Stream0 + DMA1 Stream0 global interrupt + 11 + + + DMA1_Stream1 + DMA1 Stream1 global interrupt + 12 + + + DMA1_Stream2 + DMA1 Stream2 global interrupt + 13 + + + DMA1_Stream3 + DMA1 Stream3 global interrupt + 14 + + + DMA1_Stream4 + DMA1 Stream4 global interrupt + 15 + + + DMA1_Stream5 + DMA1 Stream5 global interrupt + 16 + + + DMA1_Stream6 + DMA1 Stream6 global interrupt + 17 + + + DMA1_Stream7 + DMA1 Stream7 global interrupt + 47 + + + + RCC + Reset and clock control + RCC + 0x40023800 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + 0x00000083 + + + PLLI2SRDY + PLLI2S clock ready flag + 27 + 1 + read-only + + + PLLI2SON + PLLI2S enable + 26 + 1 + read-write + + + PLLRDY + Main PLL (PLL) clock ready + flag + 25 + 1 + read-only + + + PLLON + Main PLL (PLL) enable + 24 + 1 + read-write + + + CSSON + Clock security system + enable + 19 + 1 + read-write + + + HSEBYP + HSE clock bypass + 18 + 1 + read-write + + + HSERDY + HSE clock ready flag + 17 + 1 + read-only + + + HSEON + HSE clock enable + 16 + 1 + read-write + + + HSICAL + Internal high-speed clock + calibration + 8 + 8 + read-only + + + HSITRIM + Internal high-speed clock + trimming + 3 + 5 + read-write + + + HSIRDY + Internal high-speed clock ready + flag + 1 + 1 + read-only + + + HSION + Internal high-speed clock + enable + 0 + 1 + read-write + + + + + PLLCFGR + PLLCFGR + PLL configuration register + 0x4 + 0x20 + read-write + 0x24003010 + + + PLLQ3 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 27 + 1 + + + PLLQ2 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 26 + 1 + + + PLLQ1 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 25 + 1 + + + PLLQ0 + Main PLL (PLL) division factor for USB + OTG FS, SDIO and random number generator + clocks + 24 + 1 + + + PLLSRC + Main PLL(PLL) and audio PLL (PLLI2S) + entry clock source + 22 + 1 + + + PLLP1 + Main PLL (PLL) division factor for main + system clock + 17 + 1 + + + PLLP0 + Main PLL (PLL) division factor for main + system clock + 16 + 1 + + + PLLN8 + Main PLL (PLL) multiplication factor for + VCO + 14 + 1 + + + PLLN7 + Main PLL (PLL) multiplication factor for + VCO + 13 + 1 + + + PLLN6 + Main PLL (PLL) multiplication factor for + VCO + 12 + 1 + + + PLLN5 + Main PLL (PLL) multiplication factor for + VCO + 11 + 1 + + + PLLN4 + Main PLL (PLL) multiplication factor for + VCO + 10 + 1 + + + PLLN3 + Main PLL (PLL) multiplication factor for + VCO + 9 + 1 + + + PLLN2 + Main PLL (PLL) multiplication factor for + VCO + 8 + 1 + + + PLLN1 + Main PLL (PLL) multiplication factor for + VCO + 7 + 1 + + + PLLN0 + Main PLL (PLL) multiplication factor for + VCO + 6 + 1 + + + PLLM5 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 5 + 1 + + + PLLM4 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 4 + 1 + + + PLLM3 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 3 + 1 + + + PLLM2 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 2 + 1 + + + PLLM1 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 1 + 1 + + + PLLM0 + Division factor for the main PLL (PLL) + and audio PLL (PLLI2S) input clock + 0 + 1 + + + + + CFGR + CFGR + clock configuration register + 0x8 + 0x20 + 0x00000000 + + + MCO2 + Microcontroller clock output + 2 + 30 + 2 + read-write + + + MCO2PRE + MCO2 prescaler + 27 + 3 + read-write + + + MCO1PRE + MCO1 prescaler + 24 + 3 + read-write + + + I2SSRC + I2S clock selection + 23 + 1 + read-write + + + MCO1 + Microcontroller clock output + 1 + 21 + 2 + read-write + + + RTCPRE + HSE division factor for RTC + clock + 16 + 5 + read-write + + + PPRE2 + APB high-speed prescaler + (APB2) + 13 + 3 + read-write + + + PPRE1 + APB Low speed prescaler + (APB1) + 10 + 3 + read-write + + + HPRE + AHB prescaler + 4 + 4 + read-write + + + SWS1 + System clock switch status + 3 + 1 + read-only + + + SWS0 + System clock switch status + 2 + 1 + read-only + + + SW1 + System clock switch + 1 + 1 + read-write + + + SW0 + System clock switch + 0 + 1 + read-write + + + + + CIR + CIR + clock interrupt register + 0xC + 0x20 + 0x00000000 + + + CSSC + Clock security system interrupt + clear + 23 + 1 + write-only + + + PLLSAIRDYC + PLLSAI Ready Interrupt + Clear + 22 + 1 + write-only + + + PLLI2SRDYC + PLLI2S ready interrupt + clear + 21 + 1 + write-only + + + PLLRDYC + Main PLL(PLL) ready interrupt + clear + 20 + 1 + write-only + + + HSERDYC + HSE ready interrupt clear + 19 + 1 + write-only + + + HSIRDYC + HSI ready interrupt clear + 18 + 1 + write-only + + + LSERDYC + LSE ready interrupt clear + 17 + 1 + write-only + + + LSIRDYC + LSI ready interrupt clear + 16 + 1 + write-only + + + PLLSAIRDYIE + PLLSAI Ready Interrupt + Enable + 14 + 1 + read-write + + + PLLI2SRDYIE + PLLI2S ready interrupt + enable + 13 + 1 + read-write + + + PLLRDYIE + Main PLL (PLL) ready interrupt + enable + 12 + 1 + read-write + + + HSERDYIE + HSE ready interrupt enable + 11 + 1 + read-write + + + HSIRDYIE + HSI ready interrupt enable + 10 + 1 + read-write + + + LSERDYIE + LSE ready interrupt enable + 9 + 1 + read-write + + + LSIRDYIE + LSI ready interrupt enable + 8 + 1 + read-write + + + CSSF + Clock security system interrupt + flag + 7 + 1 + read-only + + + PLLSAIRDYF + PLLSAI ready interrupt + flag + 6 + 1 + read-only + + + PLLI2SRDYF + PLLI2S ready interrupt + flag + 5 + 1 + read-only + + + PLLRDYF + Main PLL (PLL) ready interrupt + flag + 4 + 1 + read-only + + + HSERDYF + HSE ready interrupt flag + 3 + 1 + read-only + + + HSIRDYF + HSI ready interrupt flag + 2 + 1 + read-only + + + LSERDYF + LSE ready interrupt flag + 1 + 1 + read-only + + + LSIRDYF + LSI ready interrupt flag + 0 + 1 + read-only + + + + + AHB1RSTR + AHB1RSTR + AHB1 peripheral reset register + 0x10 + 0x20 + read-write + 0x00000000 + + + OTGHSRST + USB OTG HS module reset + 29 + 1 + + + ETHMACRST + Ethernet MAC reset + 25 + 1 + + + DMA2DRST + DMA2D reset + 23 + 1 + + + DMA2RST + DMA2 reset + 22 + 1 + + + DMA1RST + DMA2 reset + 21 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + GPIOKRST + IO port K reset + 10 + 1 + + + GPIOJRST + IO port J reset + 9 + 1 + + + GPIOIRST + IO port I reset + 8 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOARST + IO port A reset + 0 + 1 + + + + + AHB2RSTR + AHB2RSTR + AHB2 peripheral reset register + 0x14 + 0x20 + read-write + 0x00000000 + + + OTGFSRST + USB OTG FS module reset + 7 + 1 + + + RNGRST + Random number generator module + reset + 6 + 1 + + + HSAHRST + Hash module reset + 5 + 1 + + + CRYPRST + Cryptographic module reset + 4 + 1 + + + DCMIRST + Camera interface reset + 0 + 1 + + + + + AHB3RSTR + AHB3RSTR + AHB3 peripheral reset register + 0x18 + 0x20 + read-write + 0x00000000 + + + FMCRST + Flexible memory controller module + reset + 0 + 1 + + + QSPIRST + Quad SPI memory controller + reset + 1 + 1 + + + + + APB1RSTR + APB1RSTR + APB1 peripheral reset register + 0x20 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM2 reset + 0 + 1 + + + TIM3RST + TIM3 reset + 1 + 1 + + + TIM4RST + TIM4 reset + 2 + 1 + + + TIM5RST + TIM5 reset + 3 + 1 + + + TIM6RST + TIM6 reset + 4 + 1 + + + TIM7RST + TIM7 reset + 5 + 1 + + + TIM12RST + TIM12 reset + 6 + 1 + + + TIM13RST + TIM13 reset + 7 + 1 + + + TIM14RST + TIM14 reset + 8 + 1 + + + WWDGRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI 2 reset + 14 + 1 + + + SPI3RST + SPI 3 reset + 15 + 1 + + + UART2RST + USART 2 reset + 17 + 1 + + + UART3RST + USART 3 reset + 18 + 1 + + + UART4RST + USART 4 reset + 19 + 1 + + + UART5RST + USART 5 reset + 20 + 1 + + + I2C1RST + I2C 1 reset + 21 + 1 + + + I2C2RST + I2C 2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWRRST + Power interface reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + SPDIFRXRST + SPDIF-RX reset + 16 + 1 + + + CECRST + HDMI-CEC reset + 27 + 1 + + + LPTIM1RST + Low power timer 1 reset + 9 + 1 + + + I2C4RST + I2C 4 reset + 24 + 1 + + + + + APB2RSTR + APB2RSTR + APB2 peripheral reset register + 0x24 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 reset + 0 + 1 + + + TIM8RST + TIM8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC interface reset (common to all + ADCs) + 8 + 1 + + + SPI1RST + SPI 1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SYSCFGRST + System configuration controller + reset + 14 + 1 + + + TIM9RST + TIM9 reset + 16 + 1 + + + TIM10RST + TIM10 reset + 17 + 1 + + + TIM11RST + TIM11 reset + 18 + 1 + + + SPI5RST + SPI5 reset + 20 + 1 + + + SPI6RST + SPI6 reset + 21 + 1 + + + SAI1RST + SAI1 reset + 22 + 1 + + + LTDCRST + LTDC reset + 26 + 1 + + + SAI2RST + SAI2 reset + 23 + 1 + + + SDMMC1RST + SDMMC1 reset + 11 + 1 + + + + + AHB1ENR + AHB1ENR + AHB1 peripheral clock register + 0x30 + 0x20 + read-write + 0x00100000 + + + OTGHSULPIEN + USB OTG HSULPI clock + enable + 30 + 1 + + + OTGHSEN + USB OTG HS clock enable + 29 + 1 + + + ETHMACPTPEN + Ethernet PTP clock enable + 28 + 1 + + + ETHMACRXEN + Ethernet Reception clock + enable + 27 + 1 + + + ETHMACTXEN + Ethernet Transmission clock + enable + 26 + 1 + + + ETHMACEN + Ethernet MAC clock enable + 25 + 1 + + + DMA2DEN + DMA2D clock enable + 23 + 1 + + + DMA2EN + DMA2 clock enable + 22 + 1 + + + DMA1EN + DMA1 clock enable + 21 + 1 + + + CCMDATARAMEN + CCM data RAM clock enable + 20 + 1 + + + BKPSRAMEN + Backup SRAM interface clock + enable + 18 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + GPIOKEN + IO port K clock enable + 10 + 1 + + + GPIOJEN + IO port J clock enable + 9 + 1 + + + GPIOIEN + IO port I clock enable + 8 + 1 + + + GPIOHEN + IO port H clock enable + 7 + 1 + + + GPIOGEN + IO port G clock enable + 6 + 1 + + + GPIOFEN + IO port F clock enable + 5 + 1 + + + GPIOEEN + IO port E clock enable + 4 + 1 + + + GPIODEN + IO port D clock enable + 3 + 1 + + + GPIOCEN + IO port C clock enable + 2 + 1 + + + GPIOBEN + IO port B clock enable + 1 + 1 + + + GPIOAEN + IO port A clock enable + 0 + 1 + + + + + AHB2ENR + AHB2ENR + AHB2 peripheral clock enable + register + 0x34 + 0x20 + read-write + 0x00000000 + + + OTGFSEN + USB OTG FS clock enable + 7 + 1 + + + RNGEN + Random number generator clock + enable + 6 + 1 + + + HASHEN + Hash modules clock enable + 5 + 1 + + + CRYPEN + Cryptographic modules clock + enable + 4 + 1 + + + DCMIEN + Camera interface enable + 0 + 1 + + + + + AHB3ENR + AHB3ENR + AHB3 peripheral clock enable + register + 0x38 + 0x20 + read-write + 0x00000000 + + + FMCEN + Flexible memory controller module clock + enable + 0 + 1 + + + QSPIEN + Quad SPI memory controller clock + enable + 1 + 1 + + + + + APB1ENR + APB1ENR + APB1 peripheral clock enable + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM2 clock enable + 0 + 1 + + + TIM3EN + TIM3 clock enable + 1 + 1 + + + TIM4EN + TIM4 clock enable + 2 + 1 + + + TIM5EN + TIM5 clock enable + 3 + 1 + + + TIM6EN + TIM6 clock enable + 4 + 1 + + + TIM7EN + TIM7 clock enable + 5 + 1 + + + TIM12EN + TIM12 clock enable + 6 + 1 + + + TIM13EN + TIM13 clock enable + 7 + 1 + + + TIM14EN + TIM14 clock enable + 8 + 1 + + + WWDGEN + Window watchdog clock + enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART 2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN 1 clock enable + 25 + 1 + + + CAN2EN + CAN 2 clock enable + 26 + 1 + + + PWREN + Power interface clock + enable + 28 + 1 + + + DACEN + DAC interface clock enable + 29 + 1 + + + UART7ENR + UART7 clock enable + 30 + 1 + + + UART8ENR + UART8 clock enable + 31 + 1 + + + SPDIFRXEN + SPDIF-RX clock enable + 16 + 1 + + + CECEN + HDMI-CEN clock enable + 27 + 1 + + + LPTMI1EN + Low power timer 1 clock + enable + 9 + 1 + + + I2C4EN + I2C4 clock enable + 24 + 1 + + + + + APB2ENR + APB2ENR + APB2 peripheral clock enable + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 clock enable + 0 + 1 + + + TIM8EN + TIM8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4ENR + SPI4 clock enable + 13 + 1 + + + SYSCFGEN + System configuration controller clock + enable + 14 + 1 + + + TIM9EN + TIM9 clock enable + 16 + 1 + + + TIM10EN + TIM10 clock enable + 17 + 1 + + + TIM11EN + TIM11 clock enable + 18 + 1 + + + SPI5ENR + SPI5 clock enable + 20 + 1 + + + SPI6ENR + SPI6 clock enable + 21 + 1 + + + SAI1EN + SAI1 clock enable + 22 + 1 + + + LTDCEN + LTDC clock enable + 26 + 1 + + + SAI2EN + SAI2 clock enable + 23 + 1 + + + SDMMC1EN + SDMMC1 clock enable + 11 + 1 + + + + + AHB1LPENR + AHB1LPENR + AHB1 peripheral clock enable in low power + mode register + 0x50 + 0x20 + read-write + 0x7E6791FF + + + GPIOALPEN + IO port A clock enable during sleep + mode + 0 + 1 + + + GPIOBLPEN + IO port B clock enable during Sleep + mode + 1 + 1 + + + GPIOCLPEN + IO port C clock enable during Sleep + mode + 2 + 1 + + + GPIODLPEN + IO port D clock enable during Sleep + mode + 3 + 1 + + + GPIOELPEN + IO port E clock enable during Sleep + mode + 4 + 1 + + + GPIOFLPEN + IO port F clock enable during Sleep + mode + 5 + 1 + + + GPIOGLPEN + IO port G clock enable during Sleep + mode + 6 + 1 + + + GPIOHLPEN + IO port H clock enable during Sleep + mode + 7 + 1 + + + GPIOILPEN + IO port I clock enable during Sleep + mode + 8 + 1 + + + GPIOJLPEN + IO port J clock enable during Sleep + mode + 9 + 1 + + + GPIOKLPEN + IO port K clock enable during Sleep + mode + 10 + 1 + + + CRCLPEN + CRC clock enable during Sleep + mode + 12 + 1 + + + FLITFLPEN + Flash interface clock enable during + Sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM 1interface clock enable during + Sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM 2 interface clock enable during + Sleep mode + 17 + 1 + + + BKPSRAMLPEN + Backup SRAM interface clock enable + during Sleep mode + 18 + 1 + + + SRAM3LPEN + SRAM 3 interface clock enable during + Sleep mode + 19 + 1 + + + DMA1LPEN + DMA1 clock enable during Sleep + mode + 21 + 1 + + + DMA2LPEN + DMA2 clock enable during Sleep + mode + 22 + 1 + + + DMA2DLPEN + DMA2D clock enable during Sleep + mode + 23 + 1 + + + ETHMACLPEN + Ethernet MAC clock enable during Sleep + mode + 25 + 1 + + + ETHMACTXLPEN + Ethernet transmission clock enable + during Sleep mode + 26 + 1 + + + ETHMACRXLPEN + Ethernet reception clock enable during + Sleep mode + 27 + 1 + + + ETHMACPTPLPEN + Ethernet PTP clock enable during Sleep + mode + 28 + 1 + + + OTGHSLPEN + USB OTG HS clock enable during Sleep + mode + 29 + 1 + + + OTGHSULPILPEN + USB OTG HS ULPI clock enable during + Sleep mode + 30 + 1 + + + + + AHB2LPENR + AHB2LPENR + AHB2 peripheral clock enable in low power + mode register + 0x54 + 0x20 + read-write + 0x000000F1 + + + OTGFSLPEN + USB OTG FS clock enable during Sleep + mode + 7 + 1 + + + RNGLPEN + Random number generator clock enable + during Sleep mode + 6 + 1 + + + HASHLPEN + Hash modules clock enable during Sleep + mode + 5 + 1 + + + CRYPLPEN + Cryptography modules clock enable during + Sleep mode + 4 + 1 + + + DCMILPEN + Camera interface enable during Sleep + mode + 0 + 1 + + + + + AHB3LPENR + AHB3LPENR + AHB3 peripheral clock enable in low power + mode register + 0x58 + 0x20 + read-write + 0x00000001 + + + FMCLPEN + Flexible memory controller module clock + enable during Sleep mode + 0 + 1 + + + QSPILPEN + Quand SPI memory controller clock enable + during Sleep mode + 1 + 1 + + + + + APB1LPENR + APB1LPENR + APB1 peripheral clock enable in low power + mode register + 0x60 + 0x20 + read-write + 0x36FEC9FF + + + TIM2LPEN + TIM2 clock enable during Sleep + mode + 0 + 1 + + + TIM3LPEN + TIM3 clock enable during Sleep + mode + 1 + 1 + + + TIM4LPEN + TIM4 clock enable during Sleep + mode + 2 + 1 + + + TIM5LPEN + TIM5 clock enable during Sleep + mode + 3 + 1 + + + TIM6LPEN + TIM6 clock enable during Sleep + mode + 4 + 1 + + + TIM7LPEN + TIM7 clock enable during Sleep + mode + 5 + 1 + + + TIM12LPEN + TIM12 clock enable during Sleep + mode + 6 + 1 + + + TIM13LPEN + TIM13 clock enable during Sleep + mode + 7 + 1 + + + TIM14LPEN + TIM14 clock enable during Sleep + mode + 8 + 1 + + + WWDGLPEN + Window watchdog clock enable during + Sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during Sleep + mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during Sleep + mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during Sleep + mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during Sleep + mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during Sleep + mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during Sleep + mode + 20 + 1 + + + I2C1LPEN + I2C1 clock enable during Sleep + mode + 21 + 1 + + + I2C2LPEN + I2C2 clock enable during Sleep + mode + 22 + 1 + + + I2C3LPEN + I2C3 clock enable during Sleep + mode + 23 + 1 + + + CAN1LPEN + CAN 1 clock enable during Sleep + mode + 25 + 1 + + + CAN2LPEN + CAN 2 clock enable during Sleep + mode + 26 + 1 + + + PWRLPEN + Power interface clock enable during + Sleep mode + 28 + 1 + + + DACLPEN + DAC interface clock enable during Sleep + mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during Sleep + mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during Sleep + mode + 31 + 1 + + + SPDIFRXLPEN + SPDIF-RX clock enable during sleep + mode + 16 + 1 + + + CECLPEN + HDMI-CEN clock enable during Sleep + mode + 27 + 1 + + + LPTIM1LPEN + low power timer 1 clock enable during + Sleep mode + 9 + 1 + + + I2C4LPEN + I2C4 clock enable during Sleep + mode + 24 + 1 + + + + + APB2LPENR + APB2LPENR + APB2 peripheral clock enabled in low power + mode register + 0x64 + 0x20 + read-write + 0x00075F33 + + + TIM1LPEN + TIM1 clock enable during Sleep + mode + 0 + 1 + + + TIM8LPEN + TIM8 clock enable during Sleep + mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during Sleep + mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during Sleep + mode + 5 + 1 + + + ADC1LPEN + ADC1 clock enable during Sleep + mode + 8 + 1 + + + ADC2LPEN + ADC2 clock enable during Sleep + mode + 9 + 1 + + + ADC3LPEN + ADC 3 clock enable during Sleep + mode + 10 + 1 + + + SPI1LPEN + SPI 1 clock enable during Sleep + mode + 12 + 1 + + + SPI4LPEN + SPI 4 clock enable during Sleep + mode + 13 + 1 + + + SYSCFGLPEN + System configuration controller clock + enable during Sleep mode + 14 + 1 + + + TIM9LPEN + TIM9 clock enable during sleep + mode + 16 + 1 + + + TIM10LPEN + TIM10 clock enable during Sleep + mode + 17 + 1 + + + TIM11LPEN + TIM11 clock enable during Sleep + mode + 18 + 1 + + + SPI5LPEN + SPI 5 clock enable during Sleep + mode + 20 + 1 + + + SPI6LPEN + SPI 6 clock enable during Sleep + mode + 21 + 1 + + + SAI1LPEN + SAI1 clock enable during sleep + mode + 22 + 1 + + + LTDCLPEN + LTDC clock enable during sleep + mode + 26 + 1 + + + SAI2LPEN + SAI2 clock enable during sleep + mode + 23 + 1 + + + SDMMC1LPEN + SDMMC1 clock enable during Sleep + mode + 11 + 1 + + + + + BDCR + BDCR + Backup domain control register + 0x70 + 0x20 + 0x00000000 + + + BDRST + Backup domain software + reset + 16 + 1 + read-write + + + RTCEN + RTC clock enable + 15 + 1 + read-write + + + RTCSEL1 + RTC clock source selection + 9 + 1 + read-write + + + RTCSEL0 + RTC clock source selection + 8 + 1 + read-write + + + LSEBYP + External low-speed oscillator + bypass + 2 + 1 + read-write + + + LSERDY + External low-speed oscillator + ready + 1 + 1 + read-only + + + LSEON + External low-speed oscillator + enable + 0 + 1 + read-write + + + + + CSR + CSR + clock control & status + register + 0x74 + 0x20 + 0x0E000000 + + + LPWRRSTF + Low-power reset flag + 31 + 1 + read-write + + + WWDGRSTF + Window watchdog reset flag + 30 + 1 + read-write + + + WDGRSTF + Independent watchdog reset + flag + 29 + 1 + read-write + + + SFTRSTF + Software reset flag + 28 + 1 + read-write + + + PORRSTF + POR/PDR reset flag + 27 + 1 + read-write + + + PADRSTF + PIN reset flag + 26 + 1 + read-write + + + BORRSTF + BOR reset flag + 25 + 1 + read-write + + + RMVF + Remove reset flag + 24 + 1 + read-write + + + LSIRDY + Internal low-speed oscillator + ready + 1 + 1 + read-only + + + LSION + Internal low-speed oscillator + enable + 0 + 1 + read-write + + + + + SSCGR + SSCGR + spread spectrum clock generation + register + 0x80 + 0x20 + read-write + 0x00000000 + + + SSCGEN + Spread spectrum modulation + enable + 31 + 1 + + + SPREADSEL + Spread Select + 30 + 1 + + + INCSTEP + Incrementation step + 13 + 15 + + + MODPER + Modulation period + 0 + 13 + + + + + PLLI2SCFGR + PLLI2SCFGR + PLLI2S configuration register + 0x84 + 0x20 + read-write + 0x20003000 + + + PLLI2SR + PLLI2S division factor for I2S + clocks + 28 + 3 + + + PLLI2SQ + PLLI2S division factor for SAI1 + clock + 24 + 4 + + + PLLI2SN + PLLI2S multiplication factor for + VCO + 6 + 9 + + + + + PLLSAICFGR + PLLSAICFGR + PLL configuration register + 0x88 + 0x20 + read-write + 0x20003000 + + + PLLSAIN + PLLSAI division factor for + VCO + 6 + 9 + + + PLLSAIP + PLLSAI division factor for 48MHz + clock + 16 + 2 + + + PLLSAIQ + PLLSAI division factor for SAI + clock + 24 + 4 + + + PLLSAIR + PLLSAI division factor for LCD + clock + 28 + 3 + + + + + DKCFGR1 + DKCFGR1 + dedicated clocks configuration + register + 0x8C + 0x20 + read-write + 0x20003000 + + + PLLI2SDIV + PLLI2S division factor for SAI1 + clock + 0 + 5 + + + PLLSAIDIVQ + PLLSAI division factor for SAI1 + clock + 8 + 5 + + + PLLSAIDIVR + division factor for + LCD_CLK + 16 + 2 + + + SAI1SEL + SAI1 clock source + selection + 20 + 2 + + + SAI2SEL + SAI2 clock source + selection + 22 + 2 + + + TIMPRE + Timers clocks prescalers + selection + 24 + 1 + + + + + DKCFGR2 + DKCFGR2 + dedicated clocks configuration + register + 0x90 + 0x20 + read-write + 0x20003000 + + + USART1SEL + USART 1 clock source + selection + 0 + 2 + + + USART2SEL + USART 2 clock source + selection + 2 + 2 + + + USART3SEL + USART 3 clock source + selection + 4 + 2 + + + UART4SEL + UART 4 clock source + selection + 6 + 2 + + + UART5SEL + UART 5 clock source + selection + 8 + 2 + + + USART6SEL + USART 6 clock source + selection + 10 + 2 + + + UART7SEL + UART 7 clock source + selection + 12 + 2 + + + UART8SEL + UART 8 clock source + selection + 14 + 2 + + + I2C1SEL + I2C1 clock source + selection + 16 + 2 + + + I2C2SEL + I2C2 clock source + selection + 18 + 2 + + + I2C3SEL + I2C3 clock source + selection + 20 + 2 + + + I2C4SEL + I2C4 clock source + selection + 22 + 2 + + + LPTIM1SEL + Low power timer 1 clock source + selection + 24 + 2 + + + CECSEL + HDMI-CEC clock source + selection + 26 + 1 + + + CK48MSEL + 48MHz clock source + selection + 27 + 1 + + + SDMMCSEL + SDMMC clock source + selection + 28 + 1 + + + + + + + GPIOD + General-purpose I/Os + GPIO + 0X40020C00 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function + lowregister + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port D Reset bit 0 + 0 + 1 + + + BR1 + Port D Reset bit 1 + 1 + 1 + + + BR2 + Port D Reset bit 2 + 2 + 1 + + + BR3 + Port D Reset bit 3 + 3 + 1 + + + BR4 + Port D Reset bit 4 + 4 + 1 + + + BR5 + Port D Reset bit 5 + 5 + 1 + + + BR6 + Port D Reset bit 6 + 6 + 1 + + + BR7 + Port D Reset bit 7 + 7 + 1 + + + BR8 + Port D Reset bit 8 + 8 + 1 + + + BR9 + Port D Reset bit 9 + 9 + 1 + + + BR10 + Port D Reset bit 10 + 10 + 1 + + + BR11 + Port D Reset bit 11 + 11 + 1 + + + BR12 + Port D Reset bit 12 + 12 + 1 + + + BR13 + Port D Reset bit 13 + 13 + 1 + + + BR14 + Port D Reset bit 14 + 14 + 1 + + + BR15 + Port D Reset bit 15 + 15 + 1 + + + + + + + GPIOC + 0x40020800 + + + GPIOK + 0X40022800 + + + GPIOJ + 0X40022400 + + + GPIOI + 0X40022000 + + + GPIOH + 0X40021C00 + + + GPIOG + 0X40021800 + + + GPIOF + 0X40021400 + + + GPIOE + 0X40021000 + + + GPIOB + General-purpose I/Os + GPIO + 0x40020400 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0x00000280 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x000000C0 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x00000100 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port B Reset bit 0 + 0 + 1 + + + BR1 + Port B Reset bit 1 + 1 + 1 + + + BR2 + Port B Reset bit 2 + 2 + 1 + + + BR3 + Port B Reset bit 3 + 3 + 1 + + + BR4 + Port B Reset bit 4 + 4 + 1 + + + BR5 + Port B Reset bit 5 + 5 + 1 + + + BR6 + Port B Reset bit 6 + 6 + 1 + + + BR7 + Port B Reset bit 7 + 7 + 1 + + + BR8 + Port B Reset bit 8 + 8 + 1 + + + BR9 + Port B Reset bit 9 + 9 + 1 + + + BR10 + Port B Reset bit 10 + 10 + 1 + + + BR11 + Port B Reset bit 11 + 11 + 1 + + + BR12 + Port B Reset bit 12 + 12 + 1 + + + BR13 + Port B Reset bit 13 + 13 + 1 + + + BR14 + Port B Reset bit 14 + 14 + 1 + + + BR15 + Port B Reset bit 15 + 15 + 1 + + + + + + + GPIOA + General-purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xA8000000 + + + MODER15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + MODER14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + MODER13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + MODER12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + MODER11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + MODER10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + MODER9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + MODER8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + MODER7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + MODER6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + MODER5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + MODER4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + MODER3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + MODER2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + MODER1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + MODER0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT15 + Port x configuration bits (y = + 0..15) + 15 + 1 + + + OT14 + Port x configuration bits (y = + 0..15) + 14 + 1 + + + OT13 + Port x configuration bits (y = + 0..15) + 13 + 1 + + + OT12 + Port x configuration bits (y = + 0..15) + 12 + 1 + + + OT11 + Port x configuration bits (y = + 0..15) + 11 + 1 + + + OT10 + Port x configuration bits (y = + 0..15) + 10 + 1 + + + OT9 + Port x configuration bits (y = + 0..15) + 9 + 1 + + + OT8 + Port x configuration bits (y = + 0..15) + 8 + 1 + + + OT7 + Port x configuration bits (y = + 0..15) + 7 + 1 + + + OT6 + Port x configuration bits (y = + 0..15) + 6 + 1 + + + OT5 + Port x configuration bits (y = + 0..15) + 5 + 1 + + + OT4 + Port x configuration bits (y = + 0..15) + 4 + 1 + + + OT3 + Port x configuration bits (y = + 0..15) + 3 + 1 + + + OT2 + Port x configuration bits (y = + 0..15) + 2 + 1 + + + OT1 + Port x configuration bits (y = + 0..15) + 1 + 1 + + + OT0 + Port x configuration bits (y = + 0..15) + 0 + 1 + + + + + GPIOB_OSPEEDR + GPIOB_OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x00000000 + + + OSPEEDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + OSPEEDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + OSPEEDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + OSPEEDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + OSPEEDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + OSPEEDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + OSPEEDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + OSPEEDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + OSPEEDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + OSPEEDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + OSPEEDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + OSPEEDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + OSPEEDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + OSPEEDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + OSPEEDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + OSPEEDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x64000000 + + + PUPDR15 + Port x configuration bits (y = + 0..15) + 30 + 2 + + + PUPDR14 + Port x configuration bits (y = + 0..15) + 28 + 2 + + + PUPDR13 + Port x configuration bits (y = + 0..15) + 26 + 2 + + + PUPDR12 + Port x configuration bits (y = + 0..15) + 24 + 2 + + + PUPDR11 + Port x configuration bits (y = + 0..15) + 22 + 2 + + + PUPDR10 + Port x configuration bits (y = + 0..15) + 20 + 2 + + + PUPDR9 + Port x configuration bits (y = + 0..15) + 18 + 2 + + + PUPDR8 + Port x configuration bits (y = + 0..15) + 16 + 2 + + + PUPDR7 + Port x configuration bits (y = + 0..15) + 14 + 2 + + + PUPDR6 + Port x configuration bits (y = + 0..15) + 12 + 2 + + + PUPDR5 + Port x configuration bits (y = + 0..15) + 10 + 2 + + + PUPDR4 + Port x configuration bits (y = + 0..15) + 8 + 2 + + + PUPDR3 + Port x configuration bits (y = + 0..15) + 6 + 2 + + + PUPDR2 + Port x configuration bits (y = + 0..15) + 4 + 2 + + + PUPDR1 + Port x configuration bits (y = + 0..15) + 2 + 2 + + + PUPDR0 + Port x configuration bits (y = + 0..15) + 0 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDR15 + Port input data (y = + 0..15) + 15 + 1 + + + IDR14 + Port input data (y = + 0..15) + 14 + 1 + + + IDR13 + Port input data (y = + 0..15) + 13 + 1 + + + IDR12 + Port input data (y = + 0..15) + 12 + 1 + + + IDR11 + Port input data (y = + 0..15) + 11 + 1 + + + IDR10 + Port input data (y = + 0..15) + 10 + 1 + + + IDR9 + Port input data (y = + 0..15) + 9 + 1 + + + IDR8 + Port input data (y = + 0..15) + 8 + 1 + + + IDR7 + Port input data (y = + 0..15) + 7 + 1 + + + IDR6 + Port input data (y = + 0..15) + 6 + 1 + + + IDR5 + Port input data (y = + 0..15) + 5 + 1 + + + IDR4 + Port input data (y = + 0..15) + 4 + 1 + + + IDR3 + Port input data (y = + 0..15) + 3 + 1 + + + IDR2 + Port input data (y = + 0..15) + 2 + 1 + + + IDR1 + Port input data (y = + 0..15) + 1 + 1 + + + IDR0 + Port input data (y = + 0..15) + 0 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODR15 + Port output data (y = + 0..15) + 15 + 1 + + + ODR14 + Port output data (y = + 0..15) + 14 + 1 + + + ODR13 + Port output data (y = + 0..15) + 13 + 1 + + + ODR12 + Port output data (y = + 0..15) + 12 + 1 + + + ODR11 + Port output data (y = + 0..15) + 11 + 1 + + + ODR10 + Port output data (y = + 0..15) + 10 + 1 + + + ODR9 + Port output data (y = + 0..15) + 9 + 1 + + + ODR8 + Port output data (y = + 0..15) + 8 + 1 + + + ODR7 + Port output data (y = + 0..15) + 7 + 1 + + + ODR6 + Port output data (y = + 0..15) + 6 + 1 + + + ODR5 + Port output data (y = + 0..15) + 5 + 1 + + + ODR4 + Port output data (y = + 0..15) + 4 + 1 + + + ODR3 + Port output data (y = + 0..15) + 3 + 1 + + + ODR2 + Port output data (y = + 0..15) + 2 + 1 + + + ODR1 + Port output data (y = + 0..15) + 1 + 1 + + + ODR0 + Port output data (y = + 0..15) + 0 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BR15 + Port x reset bit y (y = + 0..15) + 31 + 1 + + + BR14 + Port x reset bit y (y = + 0..15) + 30 + 1 + + + BR13 + Port x reset bit y (y = + 0..15) + 29 + 1 + + + BR12 + Port x reset bit y (y = + 0..15) + 28 + 1 + + + BR11 + Port x reset bit y (y = + 0..15) + 27 + 1 + + + BR10 + Port x reset bit y (y = + 0..15) + 26 + 1 + + + BR9 + Port x reset bit y (y = + 0..15) + 25 + 1 + + + BR8 + Port x reset bit y (y = + 0..15) + 24 + 1 + + + BR7 + Port x reset bit y (y = + 0..15) + 23 + 1 + + + BR6 + Port x reset bit y (y = + 0..15) + 22 + 1 + + + BR5 + Port x reset bit y (y = + 0..15) + 21 + 1 + + + BR4 + Port x reset bit y (y = + 0..15) + 20 + 1 + + + BR3 + Port x reset bit y (y = + 0..15) + 19 + 1 + + + BR2 + Port x reset bit y (y = + 0..15) + 18 + 1 + + + BR1 + Port x reset bit y (y = + 0..15) + 17 + 1 + + + BR0 + Port x set bit y (y= + 0..15) + 16 + 1 + + + BS15 + Port x set bit y (y= + 0..15) + 15 + 1 + + + BS14 + Port x set bit y (y= + 0..15) + 14 + 1 + + + BS13 + Port x set bit y (y= + 0..15) + 13 + 1 + + + BS12 + Port x set bit y (y= + 0..15) + 12 + 1 + + + BS11 + Port x set bit y (y= + 0..15) + 11 + 1 + + + BS10 + Port x set bit y (y= + 0..15) + 10 + 1 + + + BS9 + Port x set bit y (y= + 0..15) + 9 + 1 + + + BS8 + Port x set bit y (y= + 0..15) + 8 + 1 + + + BS7 + Port x set bit y (y= + 0..15) + 7 + 1 + + + BS6 + Port x set bit y (y= + 0..15) + 6 + 1 + + + BS5 + Port x set bit y (y= + 0..15) + 5 + 1 + + + BS4 + Port x set bit y (y= + 0..15) + 4 + 1 + + + BS3 + Port x set bit y (y= + 0..15) + 3 + 1 + + + BS2 + Port x set bit y (y= + 0..15) + 2 + 1 + + + BS1 + Port x set bit y (y= + 0..15) + 1 + 1 + + + BS0 + Port x set bit y (y= + 0..15) + 0 + 1 + + + + + LCKR + LCKR + GPIO port configuration lock + register + 0x1C + 0x20 + read-write + 0x00000000 + + + LCKK + Port x lock bit y (y= + 0..15) + 16 + 1 + + + LCK15 + Port x lock bit y (y= + 0..15) + 15 + 1 + + + LCK14 + Port x lock bit y (y= + 0..15) + 14 + 1 + + + LCK13 + Port x lock bit y (y= + 0..15) + 13 + 1 + + + LCK12 + Port x lock bit y (y= + 0..15) + 12 + 1 + + + LCK11 + Port x lock bit y (y= + 0..15) + 11 + 1 + + + LCK10 + Port x lock bit y (y= + 0..15) + 10 + 1 + + + LCK9 + Port x lock bit y (y= + 0..15) + 9 + 1 + + + LCK8 + Port x lock bit y (y= + 0..15) + 8 + 1 + + + LCK7 + Port x lock bit y (y= + 0..15) + 7 + 1 + + + LCK6 + Port x lock bit y (y= + 0..15) + 6 + 1 + + + LCK5 + Port x lock bit y (y= + 0..15) + 5 + 1 + + + LCK4 + Port x lock bit y (y= + 0..15) + 4 + 1 + + + LCK3 + Port x lock bit y (y= + 0..15) + 3 + 1 + + + LCK2 + Port x lock bit y (y= + 0..15) + 2 + 1 + + + LCK1 + Port x lock bit y (y= + 0..15) + 1 + 1 + + + LCK0 + Port x lock bit y (y= + 0..15) + 0 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFRL7 + Alternate function selection for port x + bit y (y = 0..7) + 28 + 4 + + + AFRL6 + Alternate function selection for port x + bit y (y = 0..7) + 24 + 4 + + + AFRL5 + Alternate function selection for port x + bit y (y = 0..7) + 20 + 4 + + + AFRL4 + Alternate function selection for port x + bit y (y = 0..7) + 16 + 4 + + + AFRL3 + Alternate function selection for port x + bit y (y = 0..7) + 12 + 4 + + + AFRL2 + Alternate function selection for port x + bit y (y = 0..7) + 8 + 4 + + + AFRL1 + Alternate function selection for port x + bit y (y = 0..7) + 4 + 4 + + + AFRL0 + Alternate function selection for port x + bit y (y = 0..7) + 0 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFRH15 + Alternate function selection for port x + bit y (y = 8..15) + 28 + 4 + + + AFRH14 + Alternate function selection for port x + bit y (y = 8..15) + 24 + 4 + + + AFRH13 + Alternate function selection for port x + bit y (y = 8..15) + 20 + 4 + + + AFRH12 + Alternate function selection for port x + bit y (y = 8..15) + 16 + 4 + + + AFRH11 + Alternate function selection for port x + bit y (y = 8..15) + 12 + 4 + + + AFRH10 + Alternate function selection for port x + bit y (y = 8..15) + 8 + 4 + + + AFRH9 + Alternate function selection for port x + bit y (y = 8..15) + 4 + 4 + + + AFRH8 + Alternate function selection for port x + bit y (y = 8..15) + 0 + 4 + + + + + BRR + BRR + GPIO port bit reset register + 0x28 + 0x20 + read-write + 0x00000000 + + + BR0 + Port A Reset bit 0 + 0 + 1 + + + BR1 + Port A Reset bit 1 + 1 + 1 + + + BR2 + Port A Reset bit 2 + 2 + 1 + + + BR3 + Port A Reset bit 3 + 3 + 1 + + + BR4 + Port A Reset bit 4 + 4 + 1 + + + BR5 + Port A Reset bit 5 + 5 + 1 + + + BR6 + Port A Reset bit 6 + 6 + 1 + + + BR7 + Port A Reset bit 7 + 7 + 1 + + + BR8 + Port A Reset bit 8 + 8 + 1 + + + BR9 + Port A Reset bit 9 + 9 + 1 + + + BR10 + Port A Reset bit 10 + 10 + 1 + + + BR11 + Port A Reset bit 11 + 11 + 1 + + + BR12 + Port A Reset bit 12 + 12 + 1 + + + BR13 + Port A Reset bit 13 + 13 + 1 + + + BR14 + Port A Reset bit 14 + 14 + 1 + + + BR15 + Port A Reset bit 15 + 15 + 1 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + MEMRM + MEMRM + memory remap register + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MODE + Memory mapping selection + 0 + 3 + + + FB_MODE + Flash bank mode selection + 8 + 1 + + + SWP_FMC + FMC memory mapping swap + 10 + 2 + + + + + PMC + PMC + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + Ethernet PHY interface + selection + 23 + 1 + + + ADC1DC2 + ADC1DC2 + 16 + 1 + + + ADC2DC2 + ADC2DC2 + 17 + 1 + + + ADC3DC2 + ADC3DC2 + 18 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CMPCR + CMPCR + Compensation cell control + register + 0x20 + 0x20 + read-only + 0x00000000 + + + READY + READY + 8 + 1 + + + CMP_PD + Compensation cell + power-down + 0 + 1 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + FRE + Frame format error + 8 + 1 + read-only + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + SPI4 + 0x40013400 + + SPI4 + SPI 4 global interrupt + 84 + + + + SPI5 + 0x40015000 + + SPI5 + SPI 5 global interrupt + 85 + + + + SPI6 + 0x40015400 + + SPI6 + SPI 6 global interrupt + 86 + + + + SPI2 + Serial peripheral interface + SPI + 0x40003800 + + 0x0 + 0x400 + registers + + + SPI2 + SPI2 global interrupt + 36 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + BIDIMODE + Bidirectional data mode + enable + 15 + 1 + + + BIDIOE + Output enable in bidirectional + mode + 14 + 1 + + + CRCEN + Hardware CRC calculation + enable + 13 + 1 + + + CRCNEXT + CRC transfer next + 12 + 1 + + + CRCL + CRC length + 11 + 1 + + + RXONLY + Receive only + 10 + 1 + + + SSM + Software slave management + 9 + 1 + + + SSI + Internal slave select + 8 + 1 + + + LSBFIRST + Frame format + 7 + 1 + + + SPE + SPI enable + 6 + 1 + + + BR + Baud rate control + 3 + 3 + + + MSTR + Master selection + 2 + 1 + + + CPOL + Clock polarity + 1 + 1 + + + CPHA + Clock phase + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0700 + + + RXDMAEN + Rx buffer DMA enable + 0 + 1 + + + TXDMAEN + Tx buffer DMA enable + 1 + 1 + + + SSOE + SS output enable + 2 + 1 + + + NSSP + NSS pulse management + 3 + 1 + + + FRF + Frame format + 4 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + RXNEIE + RX buffer not empty interrupt + enable + 6 + 1 + + + TXEIE + Tx buffer empty interrupt + enable + 7 + 1 + + + DS + Data size + 8 + 4 + + + FRXTH + FIFO reception threshold + 12 + 1 + + + LDMA_RX + Last DMA transfer for + reception + 13 + 1 + + + LDMA_TX + Last DMA transfer for + transmission + 14 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + 0x0002 + + + BSY + Busy flag + 7 + 1 + read-only + + + OVR + Overrun flag + 6 + 1 + read-only + + + MODF + Mode fault + 5 + 1 + read-only + + + CRCERR + CRC error flag + 4 + 1 + read-write + + + UDR + Underrun flag + 3 + 1 + read-only + + + CHSIDE + Channel side + 2 + 1 + read-only + + + TXE + Transmit buffer empty + 1 + 1 + read-only + + + RXNE + Receive buffer not empty + 0 + 1 + read-only + + + FRE + Frame format error + 8 + 1 + read-only + + + FRLVL + FIFO reception level + 9 + 2 + read-only + + + FTLVL + FIFO Transmission Level + 11 + 2 + read-only + + + + + DR + DR + data register + 0xC + 0x20 + read-write + 0x0000 + + + DR + Data register + 0 + 16 + + + + + CRCPR + CRCPR + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CRCPOLY + CRC polynomial register + 0 + 16 + + + + + RXCRCR + RXCRCR + RX CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RxCRC + Rx CRC register + 0 + 16 + + + + + TXCRCR + TXCRCR + TX CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TxCRC + Tx CRC register + 0 + 16 + + + + + I2SCFGR + I2SCFGR + I2S configuration register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMOD + I2S mode selection + 11 + 1 + + + I2SE + I2S Enable + 10 + 1 + + + I2SCFG + I2S configuration mode + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + CKPOL + Steady state clock + polarity + 3 + 1 + + + DATLEN + Data length to be + transferred + 1 + 2 + + + CHLEN + Channel length (number of bits per audio + channel) + 0 + 1 + + + ASTRTEN + Asynchronous start enable + 12 + 1 + + + + + I2SPR + I2SPR + I2S prescaler register + 0x20 + 0x20 + read-write + 00000010 + + + MCKOE + Master clock output enable + 9 + 1 + + + ODD + Odd factor for the + prescaler + 8 + 1 + + + I2SDIV + I2S Linear prescaler + 0 + 8 + + + + + + + ADC1 + Analog-to-digital converter + ADC + 0x40012000 + + 0x0 + 0x100 + registers + + + ADC + ADC1 global interrupt + 18 + + + + SR + SR + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OVR + Overrun + 5 + 1 + + + STRT + Regular channel start flag + 4 + 1 + + + JSTRT + Injected channel start + flag + 3 + 1 + + + JEOC + Injected channel end of + conversion + 2 + 1 + + + EOC + Regular channel end of + conversion + 1 + 1 + + + AWD + Analog watchdog flag + 0 + 1 + + + + + CR1 + CR1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OVRIE + Overrun interrupt enable + 26 + 1 + + + RES + Resolution + 24 + 2 + + + AWDEN + Analog watchdog enable on regular + channels + 23 + 1 + + + JAWDEN + Analog watchdog enable on injected + channels + 22 + 1 + + + DISCNUM + Discontinuous mode channel + count + 13 + 3 + + + JDISCEN + Discontinuous mode on injected + channels + 12 + 1 + + + DISCEN + Discontinuous mode on regular + channels + 11 + 1 + + + JAUTO + Automatic injected group + conversion + 10 + 1 + + + AWDSGL + Enable the watchdog on a single channel + in scan mode + 9 + 1 + + + SCAN + Scan mode + 8 + 1 + + + JEOCIE + Interrupt enable for injected + channels + 7 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 6 + 1 + + + EOCIE + Interrupt enable for EOC + 5 + 1 + + + AWDCH + Analog watchdog channel select + bits + 0 + 5 + + + + + CR2 + CR2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + SWSTART + Start conversion of regular + channels + 30 + 1 + + + EXTEN + External trigger enable for regular + channels + 28 + 2 + + + EXTSEL + External event select for regular + group + 24 + 4 + + + JSWSTART + Start conversion of injected + channels + 22 + 1 + + + JEXTEN + External trigger enable for injected + channels + 20 + 2 + + + JEXTSEL + External event select for injected + group + 16 + 4 + + + ALIGN + Data alignment + 11 + 1 + + + EOCS + End of conversion + selection + 10 + 1 + + + DDS + DMA disable selection (for single ADC + mode) + 9 + 1 + + + DMA + Direct memory access mode (for single + ADC mode) + 8 + 1 + + + CONT + Continuous conversion + 1 + 1 + + + ADON + A/D Converter ON / OFF + 0 + 1 + + + + + SMPR1 + SMPR1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + SMPR2 + SMPR2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + SMPx_x + Sample time bits + 0 + 32 + + + + + JOFR1 + JOFR1 + injected channel data offset register + x + 0x14 + 0x20 + read-write + 0x00000000 + + + JOFFSET1 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR2 + JOFR2 + injected channel data offset register + x + 0x18 + 0x20 + read-write + 0x00000000 + + + JOFFSET2 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR3 + JOFR3 + injected channel data offset register + x + 0x1C + 0x20 + read-write + 0x00000000 + + + JOFFSET3 + Data offset for injected channel + x + 0 + 12 + + + + + JOFR4 + JOFR4 + injected channel data offset register + x + 0x20 + 0x20 + read-write + 0x00000000 + + + JOFFSET4 + Data offset for injected channel + x + 0 + 12 + + + + + HTR + HTR + watchdog higher threshold + register + 0x24 + 0x20 + read-write + 0x00000FFF + + + HT + Analog watchdog higher + threshold + 0 + 12 + + + + + LTR + LTR + watchdog lower threshold + register + 0x28 + 0x20 + read-write + 0x00000000 + + + LT + Analog watchdog lower + threshold + 0 + 12 + + + + + SQR1 + SQR1 + regular sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + L + Regular channel sequence + length + 20 + 4 + + + SQ16 + 16th conversion in regular + sequence + 15 + 5 + + + SQ15 + 15th conversion in regular + sequence + 10 + 5 + + + SQ14 + 14th conversion in regular + sequence + 5 + 5 + + + SQ13 + 13th conversion in regular + sequence + 0 + 5 + + + + + SQR2 + SQR2 + regular sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ12 + 12th conversion in regular + sequence + 25 + 5 + + + SQ11 + 11th conversion in regular + sequence + 20 + 5 + + + SQ10 + 10th conversion in regular + sequence + 15 + 5 + + + SQ9 + 9th conversion in regular + sequence + 10 + 5 + + + SQ8 + 8th conversion in regular + sequence + 5 + 5 + + + SQ7 + 7th conversion in regular + sequence + 0 + 5 + + + + + SQR3 + SQR3 + regular sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ6 + 6th conversion in regular + sequence + 25 + 5 + + + SQ5 + 5th conversion in regular + sequence + 20 + 5 + + + SQ4 + 4th conversion in regular + sequence + 15 + 5 + + + SQ3 + 3rd conversion in regular + sequence + 10 + 5 + + + SQ2 + 2nd conversion in regular + sequence + 5 + 5 + + + SQ1 + 1st conversion in regular + sequence + 0 + 5 + + + + + JSQR + JSQR + injected sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + JL + Injected sequence length + 20 + 2 + + + JSQ4 + 4th conversion in injected + sequence + 15 + 5 + + + JSQ3 + 3rd conversion in injected + sequence + 10 + 5 + + + JSQ2 + 2nd conversion in injected + sequence + 5 + 5 + + + JSQ1 + 1st conversion in injected + sequence + 0 + 5 + + + + + JDR1 + JDR1 + injected data register x + 0x3C + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR2 + JDR2 + injected data register x + 0x40 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR3 + JDR3 + injected data register x + 0x44 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + JDR4 + JDR4 + injected data register x + 0x48 + 0x20 + read-only + 0x00000000 + + + JDATA + Injected data + 0 + 16 + + + + + DR + DR + regular data register + 0x4C + 0x20 + read-only + 0x00000000 + + + DATA + Regular data + 0 + 16 + + + + + + + ADC2 + 0x40012100 + + + ADC3 + 0x40012200 + + + DAC + Digital-to-analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable + 29 + 1 + + + DMAEN2 + DAC channel2 DMA enable + 28 + 1 + + + MAMP2 + DAC channel2 mask/amplitude + selector + 24 + 4 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable + 22 + 2 + + + TSEL2 + DAC channel2 trigger + selection + 19 + 3 + + + TEN2 + DAC channel2 trigger + enable + 18 + 1 + + + BOFF2 + DAC channel2 output buffer + disable + 17 + 1 + + + EN2 + DAC channel2 enable + 16 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable + 13 + 1 + + + DMAEN1 + DAC channel1 DMA enable + 12 + 1 + + + MAMP1 + DAC channel1 mask/amplitude + selector + 8 + 4 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable + 6 + 2 + + + TSEL1 + DAC channel1 trigger + selection + 3 + 3 + + + TEN1 + DAC channel1 trigger + enable + 2 + 1 + + + BOFF1 + DAC channel1 output buffer + disable + 1 + 1 + + + EN1 + DAC channel1 enable + 0 + 1 + + + + + SWTRIGR + SWTRIGR + software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG2 + DAC channel2 software + trigger + 1 + 1 + + + SWTRIG1 + DAC channel1 software + trigger + 0 + 1 + + + + + DHR12R1 + DHR12R1 + channel1 12-bit right-aligned data holding + register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L1 + DHR12L1 + channel1 12-bit left aligned data holding + register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R1 + DHR8R1 + channel1 8-bit right aligned data holding + register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DHR12R2 + DHR12R2 + channel2 12-bit right aligned data holding + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 0 + 12 + + + + + DHR12L2 + DHR12L2 + channel2 12-bit left aligned data holding + register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 4 + 12 + + + + + DHR8R2 + DHR8R2 + channel2 8-bit right-aligned data holding + register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned + data + 16 + 12 + + + DACC1DHR + DAC channel1 12-bit right-aligned + data + 0 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned + data + 20 + 12 + + + DACC1DHR + DAC channel1 12-bit left-aligned + data + 4 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned + data + 8 + 8 + + + DACC1DHR + DAC channel1 8-bit right-aligned + data + 0 + 8 + + + + + DOR1 + DOR1 + channel1 data output register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output + 0 + 12 + + + + + DOR2 + DOR2 + channel2 data output register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output + 0 + 12 + + + + + SR + SR + status register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR2 + DAC channel2 DMA underrun + flag + 29 + 1 + + + DMAUDR1 + DAC channel1 DMA underrun + flag + 13 + 1 + + + + + + + PWR + Power control + PWR + 0x40007000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + power control register + 0x0 + 0x20 + read-write + 0x0000C000 + + + LPDS + Low-power deep sleep + 0 + 1 + + + PDDS + Power down deepsleep + 1 + 1 + + + CSBF + Clear standby flag + 3 + 1 + + + PVDE + Power voltage detector + enable + 4 + 1 + + + PLS + PVD level selection + 5 + 3 + + + DBP + Disable backup domain write + protection + 8 + 1 + + + FPDS + Flash power down in Stop + mode + 9 + 1 + + + LPUDS + Low-power regulator in deepsleep + under-drive mode + 10 + 1 + + + MRUDS + Main regulator in deepsleep under-drive + mode + 11 + 1 + + + ADCDC1 + ADCDC1 + 13 + 1 + + + VOS + Regulator voltage scaling output + selection + 14 + 2 + + + ODEN + Over-drive enable + 16 + 1 + + + ODSWEN + Over-drive switching + enabled + 17 + 1 + + + UDEN + Under-drive enable in stop + mode + 18 + 2 + + + + + CSR1 + CSR1 + power control/status register + 0x4 + 0x20 + 0x00000000 + + + WUIF + Wakeup internal flag + 0 + 1 + read-only + + + SBF + Standby flag + 1 + 1 + read-only + + + PVDO + PVD output + 2 + 1 + read-only + + + BRR + Backup regulator ready + 3 + 1 + read-only + + + BRE + Backup regulator enable + 9 + 1 + read-write + + + VOSRDY + Regulator voltage scaling output + selection ready bit + 14 + 1 + read-write + + + ODRDY + Over-drive mode ready + 16 + 1 + read-write + + + ODSWRDY + Over-drive mode switching + ready + 17 + 1 + read-write + + + UDRDY + Under-drive ready flag + 18 + 2 + read-write + + + + + CR2 + CR2 + power control register + 0x8 + 0x20 + 0x00000000 + + + CWUPF1 + Clear Wakeup Pin flag for + PA0 + 0 + 1 + read-only + + + CWUPF2 + Clear Wakeup Pin flag for + PA2 + 1 + 1 + read-only + + + CWUPF3 + Clear Wakeup Pin flag for + PC1 + 2 + 1 + read-only + + + CWUPF4 + Clear Wakeup Pin flag for + PC13 + 3 + 1 + read-only + + + CWUPF5 + Clear Wakeup Pin flag for + PI8 + 4 + 1 + read-only + + + CWUPF6 + Clear Wakeup Pin flag for + PI11 + 5 + 1 + read-only + + + WUPP1 + Wakeup pin polarity bit for + PA0 + 8 + 1 + read-write + + + WUPP2 + Wakeup pin polarity bit for + PA2 + 9 + 1 + read-write + + + WUPP3 + Wakeup pin polarity bit for + PC1 + 10 + 1 + read-write + + + WUPP4 + Wakeup pin polarity bit for + PC13 + 11 + 1 + read-write + + + WUPP5 + Wakeup pin polarity bit for + PI8 + 12 + 1 + read-write + + + WUPP6 + Wakeup pin polarity bit for + PI11 + 13 + 1 + read-write + + + + + CSR2 + CSR2 + power control/status register + 0xC + 0x20 + 0x00000000 + + + WUPF1 + Wakeup Pin flag for PA0 + 0 + 1 + read-only + + + WUPF2 + Wakeup Pin flag for PA2 + 1 + 1 + read-only + + + WUPF3 + Wakeup Pin flag for PC1 + 2 + 1 + read-only + + + WUPF4 + Wakeup Pin flag for PC13 + 3 + 1 + read-only + + + WUPF5 + Wakeup Pin flag for PI8 + 4 + 1 + read-only + + + WUPF6 + Wakeup Pin flag for PI11 + 5 + 1 + read-only + + + EWUP1 + Enable Wakeup pin for PA0 + 8 + 1 + read-write + + + EWUP2 + Enable Wakeup pin for PA2 + 9 + 1 + read-write + + + EWUP3 + Enable Wakeup pin for PC1 + 10 + 1 + read-write + + + EWUP4 + Enable Wakeup pin for PC13 + 11 + 1 + read-write + + + EWUP5 + Enable Wakeup pin for PI8 + 12 + 1 + read-write + + + EWUP6 + Enable Wakeup pin for PI11 + 13 + 1 + read-write + + + + + + + IWDG + Independent watchdog + IWDG + 0x40003000 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read + 0000h) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload + value + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + RVU + Watchdog counter reload value + update + 1 + 1 + + + PVU + Watchdog prescaler value + update + 0 + 1 + + + + + WINR + WINR + Window register + 0x10 + 0x20 + read-write + 0x00000000 + + + WIN + Watchdog counter window + value + 0 + 12 + + + + + + + WWDG + Window watchdog + WWDG + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDG + Window Watchdog interrupt + 0 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x7F + + + WDGA + Activation bit + 7 + 1 + + + T + 7-bit counter (MSB to LSB) + 0 + 7 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x7F + + + EWI + Early wakeup interrupt + 9 + 1 + + + WDGTB1 + Timer base + 8 + 1 + + + WDGTB0 + Timer base + 7 + 1 + + + W + 7-bit window value + 0 + 7 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00 + + + EWIF + Early wakeup interrupt + flag + 0 + 1 + + + + + + + C_ADC + Common ADC registers + ADC + 0x40012300 + + 0x0 + 0x400 + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + OVR3 + Overrun flag of ADC3 + 21 + 1 + + + STRT3 + Regular channel Start flag of ADC + 3 + 20 + 1 + + + JSTRT3 + Injected channel Start flag of ADC + 3 + 19 + 1 + + + JEOC3 + Injected channel end of conversion of + ADC 3 + 18 + 1 + + + EOC3 + End of conversion of ADC 3 + 17 + 1 + + + AWD3 + Analog watchdog flag of ADC + 3 + 16 + 1 + + + OVR2 + Overrun flag of ADC 2 + 13 + 1 + + + STRT2 + Regular channel Start flag of ADC + 2 + 12 + 1 + + + JSTRT2 + Injected channel Start flag of ADC + 2 + 11 + 1 + + + JEOC2 + Injected channel end of conversion of + ADC 2 + 10 + 1 + + + EOC2 + End of conversion of ADC 2 + 9 + 1 + + + AWD2 + Analog watchdog flag of ADC + 2 + 8 + 1 + + + OVR1 + Overrun flag of ADC 1 + 5 + 1 + + + STRT1 + Regular channel Start flag of ADC + 1 + 4 + 1 + + + JSTRT1 + Injected channel Start flag of ADC + 1 + 3 + 1 + + + JEOC1 + Injected channel end of conversion of + ADC 1 + 2 + 1 + + + EOC1 + End of conversion of ADC 1 + 1 + 1 + + + AWD1 + Analog watchdog flag of ADC + 1 + 0 + 1 + + + + + CCR + CCR + ADC common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + TSVREFE + Temperature sensor and VREFINT + enable + 23 + 1 + + + VBATE + VBAT enable + 22 + 1 + + + ADCPRE + ADC prescaler + 16 + 2 + + + DMA + Direct memory access mode for multi ADC + mode + 14 + 2 + + + DDS + DMA disable selection for multi-ADC + mode + 13 + 1 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + MULT + Multi ADC mode selection + 0 + 5 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0x8 + 0x20 + read-only + 0x00000000 + + + DATA2 + 2nd data item of a pair of regular + conversions + 16 + 16 + + + DATA1 + 1st data item of a pair of regular + conversions + 0 + 16 + + + + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK_TIM9 + TIM1 Break interrupt and TIM9 global + interrupt + 24 + + + TIM1_TRG_COM_TIM11 + TIM1 Trigger and Commutation interrupts and + TIM11 global interrupt + 26 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection - + bit[2:0] + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x0000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M3 + Output Compare 5 mode + 16 + 1 + + + OC6M3 + Output Compare 6 mode + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x0000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CRR6 + CRR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x0000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + + + TIM8 + 0x40010400 + + TIM8_BRK_TIM12 + TIM8 Break interrupt and TIM12 global + interrupt + 43 + + + TIM8_UP_TIM13 + TIM8 Update interrupt and TIM13 global + interrupt + 44 + + + TIM8_TRG_COM_TIM14 + TIM8 Trigger and Commutation interrupts and + TIM14 global interrupt + 45 + + + TIM8_CC + TIM8 Capture Compare interrupt + 46 + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR1 + OR1 + TIM2 option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + TI4_RMP + Input Capture 4 remap + 2 + 2 + + + ETR1_RMP + External trigger remap + 1 + 1 + + + ITR1_RMP + Internal trigger 1 remap + 0 + 1 + + + + + OR2 + OR2 + TIM2 option register 2 + 0x60 + 0x20 + read-write + 0x0000 + + + ETRSEL + ETR source selection + 14 + 3 + + + + + + + TIM3 + General purpose timers + TIM + 0x40000400 + + 0x0 + 0x400 + registers + + + TIM3 + TIM3 global interrupt + 29 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + OR1 + OR1 + TIM3 option register 1 + 0x50 + 0x20 + read-write + 0x0000 + + + TI1_RMP + Input Capture 1 remap + 0 + 2 + + + + + OR2 + OR2 + TIM3 option register 2 + 0x60 + 0x20 + read-write + 0x0000 + + + ETRSEL + ETR source selection + 14 + 3 + + + + + + + TIM4 + General purpose timers + TIM + 0x40000800 + + 0x0 + 0x400 + registers + + + TIM4 + TIM4 global interrupt + 30 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave model selection - + bit[3] + 16 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2CE + OC2CE + 15 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2PE + OC2PE + 11 + 1 + + + OC2FE + OC2FE + 10 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC1CE + OC1CE + 7 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1PE + OC1PE + 3 + 1 + + + OC1FE + OC1FE + 2 + 1 + + + CC1S + CC1S + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_H + High counter value + 16 + 16 + + + CNT_L + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + + + TIM5 + 0x40000C00 + + TIM5 + TIM5 global interrupt + 50 + + + + TIM9 + General purpose timers + TIM + 0x40014000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 3 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 3 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + + + TIM12 + 0x40001800 + + + TIM10 + General-purpose-timers + TIM + 0x40014400 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x00000000 + + + SMS3 + Slave mode selection + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + OR + OR + option register + 0x50 + 0x20 + read-write + 0x00000000 + + + TI1_RMP + TIM11 Input 1 remapping + capability + 0 + 2 + + + + + + + TIM11 + 0x40014800 + + + TIM13 + 0x40001C00 + + + TIM14 + 0x40002000 + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt, DAC1 and DAC2 underrun + error interrupt + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + Ethernet_MAC + Ethernet: media access control + (MAC) + Ethernet + 0x40028000 + + 0x0 + 0x100 + registers + + + + MACCR + MACCR + Ethernet MAC configuration + register + 0x0 + 0x20 + read-write + 0x0008000 + + + RE + RE + 2 + 1 + + + TE + TE + 3 + 1 + + + DC + DC + 4 + 1 + + + BL + BL + 5 + 2 + + + APCS + APCS + 7 + 1 + + + RD + RD + 9 + 1 + + + IPCO + IPCO + 10 + 1 + + + DM + DM + 11 + 1 + + + LM + LM + 12 + 1 + + + ROD + ROD + 13 + 1 + + + FES + FES + 14 + 1 + + + CSD + CSD + 16 + 1 + + + IFG + IFG + 17 + 3 + + + JD + JD + 22 + 1 + + + WD + WD + 23 + 1 + + + CSTF + CSTF + 25 + 1 + + + + + MACFFR + MACFFR + Ethernet MAC frame filter + register + 0x4 + 0x20 + read-write + 0x00000000 + + + PM + PM + 0 + 1 + + + HU + HU + 1 + 1 + + + HM + HM + 2 + 1 + + + DAIF + DAIF + 3 + 1 + + + RAM + RAM + 4 + 1 + + + BFD + BFD + 5 + 1 + + + PCF + PCF + 6 + 1 + + + SAIF + SAIF + 7 + 1 + + + SAF + SAF + 8 + 1 + + + HPF + HPF + 9 + 1 + + + RA + RA + 31 + 1 + + + + + MACHTHR + MACHTHR + Ethernet MAC hash table high + register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + HTH + 0 + 32 + + + + + MACHTLR + MACHTLR + Ethernet MAC hash table low + register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + HTL + 0 + 32 + + + + + MACMIIAR + MACMIIAR + Ethernet MAC MII address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MB + 0 + 1 + + + MW + MW + 1 + 1 + + + CR + CR + 2 + 3 + + + MR + MR + 6 + 5 + + + PA + PA + 11 + 5 + + + + + MACMIIDR + MACMIIDR + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + TD + TD + 0 + 16 + + + + + MACFCR + MACFCR + Ethernet MAC flow control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB + FCB + 0 + 1 + + + TFCE + TFCE + 1 + 1 + + + RFCE + RFCE + 2 + 1 + + + UPFD + UPFD + 3 + 1 + + + PLT + PLT + 4 + 2 + + + ZQPD + ZQPD + 7 + 1 + + + PT + PT + 16 + 16 + + + + + MACVLANTR + MACVLANTR + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VLANTI + VLANTI + 0 + 16 + + + VLANTC + VLANTC + 16 + 1 + + + + + MACPMTCSR + MACPMTCSR + Ethernet MAC PMT control and status + register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + PD + 0 + 1 + + + MPE + MPE + 1 + 1 + + + WFE + WFE + 2 + 1 + + + MPR + MPR + 5 + 1 + + + WFR + WFR + 6 + 1 + + + GU + GU + 9 + 1 + + + WFFRPR + WFFRPR + 31 + 1 + + + + + MACDBGR + MACDBGR + Ethernet MAC debug register + 0x34 + 0x20 + read-only + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MACSR + MACSR + Ethernet MAC interrupt status + register + 0x38 + 0x20 + 0x00000000 + + + PMTS + PMTS + 3 + 1 + read-only + + + MMCS + MMCS + 4 + 1 + read-only + + + MMCRS + MMCRS + 5 + 1 + read-only + + + MMCTS + MMCTS + 6 + 1 + read-only + + + TSTS + TSTS + 9 + 1 + read-write + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask + register + 0x3C + 0x20 + read-write + 0x00000000 + + + PMTIM + PMTIM + 3 + 1 + + + TSTIM + TSTIM + 9 + 1 + + + + + MACA0HR + MACA0HR + Ethernet MAC address 0 high + register + 0x40 + 0x20 + 0x0010FFFF + + + MACA0H + MAC address0 high + 0 + 16 + read-write + + + MO + Always 1 + 31 + 1 + read-only + + + + + MACA0LR + MACA0LR + Ethernet MAC address 0 low + register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MACA0L + 0 + 0 + 32 + + + + + MACA1HR + MACA1HR + Ethernet MAC address 1 high + register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MACA1H + MACA1H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA1LR + MACA1LR + Ethernet MAC address1 low + register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MACA1LR + MACA1LR + 0 + 32 + + + + + MACA2HR + MACA2HR + Ethernet MAC address 2 high + register + 0x50 + 0x20 + read-write + 0x0000FFFF + + + MAC2AH + MAC2AH + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA2LR + MACA2LR + Ethernet MAC address 2 low + register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MACA2L + MACA2L + 0 + 31 + + + + + MACA3HR + MACA3HR + Ethernet MAC address 3 high + register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MACA3H + MACA3H + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3LR + MACA3LR + Ethernet MAC address 3 low + register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MBCA3L + MBCA3L + 0 + 32 + + + + + MACRWUFFER + MACRWUFFER + Ethernet MAC remote wakeup frame filter + register + 0x60 + 0x20 + read-write + 0xFFFFFFFF + + + + + Ethernet_MMC + Ethernet: MAC management counters + Ethernet + 0x40028100 + + 0x0 + 0x400 + registers + + + + MMCCR + MMCCR + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CR + CR + 0 + 1 + + + CSR + CSR + 1 + 1 + + + ROR + ROR + 2 + 1 + + + MCF + MCF + 3 + 1 + + + MCP + MCP + 4 + 1 + + + MCFHP + MCFHP + 5 + 1 + + + + + MMCRIR + MMCRIR + Ethernet MMC receive interrupt + register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCES + RFCES + 5 + 1 + + + RFAES + RFAES + 6 + 1 + + + RGUFS + RGUFS + 17 + 1 + + + + + MMCTIR + MMCTIR + Ethernet MMC transmit interrupt + register + 0x8 + 0x20 + read-only + 0x00000000 + + + TGFSCS + TGFSCS + 14 + 1 + + + TGFMSCS + TGFMSCS + 15 + 1 + + + TGFS + TGFS + 21 + 1 + + + + + MMCRIMR + MMCRIMR + Ethernet MMC receive interrupt mask + register + 0xC + 0x20 + read-write + 0x00000000 + + + RFCEM + RFCEM + 5 + 1 + + + RFAEM + RFAEM + 6 + 1 + + + RGUFM + RGUFM + 17 + 1 + + + + + MMCTIMR + MMCTIMR + Ethernet MMC transmit interrupt mask + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TGFSCM + TGFSCM + 14 + 1 + + + TGFMSCM + TGFMSCM + 15 + 1 + + + TGFM + TGFM + 16 + 1 + + + + + MMCTGFSCCR + MMCTGFSCCR + Ethernet MMC transmitted good frames after a + single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + TGFSCC + 0 + 32 + + + + + MMCTGFMSCCR + MMCTGFMSCCR + Ethernet MMC transmitted good frames after + more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + TGFMSCC + 0 + 32 + + + + + MMCTGFCR + MMCTGFCR + Ethernet MMC transmitted good frames counter + register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + HTL + 0 + 32 + + + + + MMCRFCECR + MMCRFCECR + Ethernet MMC received frames with CRC error + counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCFC + RFCFC + 0 + 32 + + + + + MMCRFAECR + MMCRFAECR + Ethernet MMC received frames with alignment + error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + RFAEC + 0 + 32 + + + + + MMCRGUFCR + MMCRGUFCR + MMC received good unicast frames counter + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + RGUFC + 0 + 32 + + + + + + + Ethernet_PTP + Ethernet: Precision time protocol + Ethernet + 0x40028700 + + 0x0 + 0x400 + registers + + + + PTPTSCR + PTPTSCR + Ethernet PTP time stamp control + register + 0x0 + 0x20 + read-write + 0x00002000 + + + TSE + TSE + 0 + 1 + + + TSFCU + TSFCU + 1 + 1 + + + TSPTPPSV2E + TSPTPPSV2E + 10 + 1 + + + TSSPTPOEFE + TSSPTPOEFE + 11 + 1 + + + TSSIPV6FE + TSSIPV6FE + 12 + 1 + + + TSSIPV4FE + TSSIPV4FE + 13 + 1 + + + TSSEME + TSSEME + 14 + 1 + + + TSSMRME + TSSMRME + 15 + 1 + + + TSCNT + TSCNT + 16 + 2 + + + TSPFFMAE + TSPFFMAE + 18 + 1 + + + TSSTI + TSSTI + 2 + 1 + + + TSSTU + TSSTU + 3 + 1 + + + TSITE + TSITE + 4 + 1 + + + TTSARU + TTSARU + 5 + 1 + + + TSSARFE + TSSARFE + 8 + 1 + + + TSSSR + TSSSR + 9 + 1 + + + + + PTPSSIR + PTPSSIR + Ethernet PTP subsecond increment + register + 0x4 + 0x20 + read-write + 0x00000000 + + + STSSI + STSSI + 0 + 8 + + + + + PTPTSHR + PTPTSHR + Ethernet PTP time stamp high + register + 0x8 + 0x20 + read-only + 0x00000000 + + + STS + STS + 0 + 32 + + + + + PTPTSLR + PTPTSLR + Ethernet PTP time stamp low + register + 0xC + 0x20 + read-only + 0x00000000 + + + STSS + STSS + 0 + 31 + + + STPNS + STPNS + 31 + 1 + + + + + PTPTSHUR + PTPTSHUR + Ethernet PTP time stamp high update + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSUS + TSUS + 0 + 32 + + + + + PTPTSLUR + PTPTSLUR + Ethernet PTP time stamp low update + register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSUSS + TSUSS + 0 + 31 + + + TSUPNS + TSUPNS + 31 + 1 + + + + + PTPTSAR + PTPTSAR + Ethernet PTP time stamp addend + register + 0x18 + 0x20 + read-write + 0x00000000 + + + TSA + TSA + 0 + 32 + + + + + PTPTTHR + PTPTTHR + Ethernet PTP target time high + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSH + 0 + 0 + 32 + + + + + PTPTTLR + PTPTTLR + Ethernet PTP target time low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTSL + TTSL + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status + register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control + register + 0x2C + 0x20 + read-only + 0x00000000 + + + TSSO + TSSO + 0 + 1 + + + TSTTR + TSTTR + 1 + 1 + + + + + + + Ethernet_DMA + Ethernet: DMA controller operation + Ethernet + 0x40029000 + + 0x0 + 0x400 + registers + + + ETH + Ethernet global interrupt + 61 + + + ETH_WKUP + Ethernet Wakeup through EXTI line + interrupt + 62 + + + + DMABMR + DMABMR + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x00002101 + + + SR + SR + 0 + 1 + + + DA + DA + 1 + 1 + + + DSL + DSL + 2 + 5 + + + EDFE + EDFE + 7 + 1 + + + PBL + PBL + 8 + 6 + + + RTPR + RTPR + 14 + 2 + + + FB + FB + 16 + 1 + + + RDP + RDP + 17 + 6 + + + USP + USP + 23 + 1 + + + FPM + FPM + 24 + 1 + + + AAB + AAB + 25 + 1 + + + MB + MB + 26 + 1 + + + + + DMATPDR + DMATPDR + Ethernet DMA transmit poll demand + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + TPD + 0 + 32 + + + + + DMARPDR + DMARPDR + EHERNET DMA receive poll demand + register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + RPD + 0 + 32 + + + + + DMARDLAR + DMARDLAR + Ethernet DMA receive descriptor list address + register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + SRL + 0 + 32 + + + + + DMATDLAR + DMATDLAR + Ethernet DMA transmit descriptor list + address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + STL + 0 + 32 + + + + + DMASR + DMASR + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TS + TS + 0 + 1 + read-write + + + TPSS + TPSS + 1 + 1 + read-write + + + TBUS + TBUS + 2 + 1 + read-write + + + TJTS + TJTS + 3 + 1 + read-write + + + ROS + ROS + 4 + 1 + read-write + + + TUS + TUS + 5 + 1 + read-write + + + RS + RS + 6 + 1 + read-write + + + RBUS + RBUS + 7 + 1 + read-write + + + RPSS + RPSS + 8 + 1 + read-write + + + PWTS + PWTS + 9 + 1 + read-write + + + ETS + ETS + 10 + 1 + read-write + + + FBES + FBES + 13 + 1 + read-write + + + ERS + ERS + 14 + 1 + read-write + + + AIS + AIS + 15 + 1 + read-write + + + NIS + NIS + 16 + 1 + read-write + + + RPS + RPS + 17 + 3 + read-only + + + TPS + TPS + 20 + 3 + read-only + + + EBS + EBS + 23 + 3 + read-only + + + MMCS + MMCS + 27 + 1 + read-only + + + PMTS + PMTS + 28 + 1 + read-only + + + TSTS + TSTS + 29 + 1 + read-only + + + + + DMAOMR + DMAOMR + Ethernet DMA operation mode + register + 0x18 + 0x20 + read-write + 0x00000000 + + + SR + SR + 1 + 1 + + + OSF + OSF + 2 + 1 + + + RTC + RTC + 3 + 2 + + + FUGF + FUGF + 6 + 1 + + + FEF + FEF + 7 + 1 + + + ST + ST + 13 + 1 + + + TTC + TTC + 14 + 3 + + + FTF + FTF + 20 + 1 + + + TSF + TSF + 21 + 1 + + + DFRF + DFRF + 24 + 1 + + + RSF + RSF + 25 + 1 + + + DTCEFD + DTCEFD + 26 + 1 + + + + + DMAIER + DMAIER + Ethernet DMA interrupt enable + register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + TIE + 0 + 1 + + + TPSIE + TPSIE + 1 + 1 + + + TBUIE + TBUIE + 2 + 1 + + + TJTIE + TJTIE + 3 + 1 + + + ROIE + ROIE + 4 + 1 + + + TUIE + TUIE + 5 + 1 + + + RIE + RIE + 6 + 1 + + + RBUIE + RBUIE + 7 + 1 + + + RPSIE + RPSIE + 8 + 1 + + + RWTIE + RWTIE + 9 + 1 + + + ETIE + ETIE + 10 + 1 + + + FBEIE + FBEIE + 13 + 1 + + + ERIE + ERIE + 14 + 1 + + + AISE + AISE + 15 + 1 + + + NISE + NISE + 16 + 1 + + + + + DMAMFBOCR + DMAMFBOCR + Ethernet DMA missed frame and buffer + overflow counter register + 0x20 + 0x20 + read-write + 0x00000000 + + + MFC + MFC + 0 + 16 + + + OMFC + OMFC + 16 + 1 + + + MFA + MFA + 17 + 11 + + + OFOC + OFOC + 28 + 1 + + + + + DMARSWTR + DMARSWTR + Ethernet DMA receive status watchdog timer + register + 0x24 + 0x20 + read-write + 0x00000000 + + + RSWTC + RSWTC + 0 + 8 + + + + + DMACHTDR + DMACHTDR + Ethernet DMA current host transmit + descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + HTDAP + 0 + 32 + + + + + DMACHRDR + DMACHRDR + Ethernet DMA current host receive descriptor + register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + HRDAP + 0 + 32 + + + + + DMACHTBAR + DMACHTBAR + Ethernet DMA current host transmit buffer + address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + HTBAP + 0 + 32 + + + + + DMACHRBAR + DMACHRBAR + Ethernet DMA current host receive buffer + address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + HRBAP + 0 + 32 + + + + + + + CRC + Cryptographic processor + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 8 + + + + + CR + CR + Control register + 0x8 + 0x20 + write-only + 0x00000000 + + + CR + Control regidter + 0 + 1 + + + + + INIT + INIT + Initial CRC value + 0xC + 0x20 + read-write + 0x00000000 + + + CRC_INIT + Programmable initial CRC + value + 0 + 32 + + + + + POL + POL + CRC polynomial + 0x10 + 0x20 + read-write + 0x00000000 + + + POL + Programmable polynomial + 0 + 32 + + + + + + + CAN1 + Controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupts + 19 + + + CAN1_RX0 + CAN1 RX0 interrupts + 20 + + + CAN1_RX1 + CAN1 RX1 interrupts + 21 + + + CAN1_SCE + CAN1 SCE interrupt + 22 + + + + MCR + MCR + master control register + 0x0 + 0x20 + read-write + 0x00010002 + + + DBF + DBF + 16 + 1 + + + RESET + RESET + 15 + 1 + + + TTCM + TTCM + 7 + 1 + + + ABOM + ABOM + 6 + 1 + + + AWUM + AWUM + 5 + 1 + + + NART + NART + 4 + 1 + + + RFLM + RFLM + 3 + 1 + + + TXFP + TXFP + 2 + 1 + + + SLEEP + SLEEP + 1 + 1 + + + INRQ + INRQ + 0 + 1 + + + + + MSR + MSR + master status register + 0x4 + 0x20 + 0x00000C02 + + + RX + RX + 11 + 1 + read-only + + + SAMP + SAMP + 10 + 1 + read-only + + + RXM + RXM + 9 + 1 + read-only + + + TXM + TXM + 8 + 1 + read-only + + + SLAKI + SLAKI + 4 + 1 + read-write + + + WKUI + WKUI + 3 + 1 + read-write + + + ERRI + ERRI + 2 + 1 + read-write + + + SLAK + SLAK + 1 + 1 + read-only + + + INAK + INAK + 0 + 1 + read-only + + + + + TSR + TSR + transmit status register + 0x8 + 0x20 + 0x1C000000 + + + LOW2 + Lowest priority flag for mailbox + 2 + 31 + 1 + read-only + + + LOW1 + Lowest priority flag for mailbox + 1 + 30 + 1 + read-only + + + LOW0 + Lowest priority flag for mailbox + 0 + 29 + 1 + read-only + + + TME2 + Lowest priority flag for mailbox + 2 + 28 + 1 + read-only + + + TME1 + Lowest priority flag for mailbox + 1 + 27 + 1 + read-only + + + TME0 + Lowest priority flag for mailbox + 0 + 26 + 1 + read-only + + + CODE + CODE + 24 + 2 + read-only + + + ABRQ2 + ABRQ2 + 23 + 1 + read-write + + + TERR2 + TERR2 + 19 + 1 + read-write + + + ALST2 + ALST2 + 18 + 1 + read-write + + + TXOK2 + TXOK2 + 17 + 1 + read-write + + + RQCP2 + RQCP2 + 16 + 1 + read-write + + + ABRQ1 + ABRQ1 + 15 + 1 + read-write + + + TERR1 + TERR1 + 11 + 1 + read-write + + + ALST1 + ALST1 + 10 + 1 + read-write + + + TXOK1 + TXOK1 + 9 + 1 + read-write + + + RQCP1 + RQCP1 + 8 + 1 + read-write + + + ABRQ0 + ABRQ0 + 7 + 1 + read-write + + + TERR0 + TERR0 + 3 + 1 + read-write + + + ALST0 + ALST0 + 2 + 1 + read-write + + + TXOK0 + TXOK0 + 1 + 1 + read-write + + + RQCP0 + RQCP0 + 0 + 1 + read-write + + + + + RF0R + RF0R + receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RFOM0 + RFOM0 + 5 + 1 + read-write + + + FOVR0 + FOVR0 + 4 + 1 + read-write + + + FULL0 + FULL0 + 3 + 1 + read-write + + + FMP0 + FMP0 + 0 + 2 + read-only + + + + + RF1R + RF1R + receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RFOM1 + RFOM1 + 5 + 1 + read-write + + + FOVR1 + FOVR1 + 4 + 1 + read-write + + + FULL1 + FULL1 + 3 + 1 + read-write + + + FMP1 + FMP1 + 0 + 2 + read-only + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + SLKIE + SLKIE + 17 + 1 + + + WKUIE + WKUIE + 16 + 1 + + + ERRIE + ERRIE + 15 + 1 + + + LECIE + LECIE + 11 + 1 + + + BOFIE + BOFIE + 10 + 1 + + + EPVIE + EPVIE + 9 + 1 + + + EWGIE + EWGIE + 8 + 1 + + + FOVIE1 + FOVIE1 + 6 + 1 + + + FFIE1 + FFIE1 + 5 + 1 + + + FMPIE1 + FMPIE1 + 4 + 1 + + + FOVIE0 + FOVIE0 + 3 + 1 + + + FFIE0 + FFIE0 + 2 + 1 + + + FMPIE0 + FMPIE0 + 1 + 1 + + + TMEIE + TMEIE + 0 + 1 + + + + + ESR + ESR + interrupt enable register + 0x18 + 0x20 + 0x00000000 + + + REC + REC + 24 + 8 + read-only + + + TEC + TEC + 16 + 8 + read-only + + + LEC + LEC + 4 + 3 + read-write + + + BOFF + BOFF + 2 + 1 + read-only + + + EPVF + EPVF + 1 + 1 + read-only + + + EWGF + EWGF + 0 + 1 + read-only + + + + + BTR + BTR + bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + SILM + SILM + 31 + 1 + + + LBKM + LBKM + 30 + 1 + + + SJW + SJW + 24 + 2 + + + TS2 + TS2 + 20 + 3 + + + TS1 + TS1 + 16 + 4 + + + BRP + BRP + 0 + 10 + + + + + TI0R + TI0R + TX mailbox identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT0R + TDT0R + mailbox data length control and time stamp + register + 0x184 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL0R + TDL0R + mailbox data low register + 0x188 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH0R + TDH0R + mailbox data high register + 0x18C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI1R + TI1R + mailbox identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT1R + TDT1R + mailbox data length control and time stamp + register + 0x194 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL1R + TDL1R + mailbox data low register + 0x198 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH1R + TDH1R + mailbox data high register + 0x19C + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + TI2R + TI2R + mailbox identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + TXRQ + TXRQ + 0 + 1 + + + + + TDT2R + TDT2R + mailbox data length control and time stamp + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TIME + TIME + 16 + 16 + + + TGT + TGT + 8 + 1 + + + DLC + DLC + 0 + 4 + + + + + TDL2R + TDL2R + mailbox data low register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + TDH2R + TDH2R + mailbox data high register + 0x1AC + 0x20 + read-write + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI0R + RI0R + receive FIFO mailbox identifier + register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT0R + RDT0R + mailbox data high register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL0R + RDL0R + mailbox data high register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH0R + RDH0R + receive FIFO mailbox data high + register + 0x1BC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + RI1R + RI1R + mailbox data high register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + STID + STID + 21 + 11 + + + EXID + EXID + 3 + 18 + + + IDE + IDE + 2 + 1 + + + RTR + RTR + 1 + 1 + + + + + RDT1R + RDT1R + mailbox data high register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + TIME + TIME + 16 + 16 + + + FMI + FMI + 8 + 8 + + + DLC + DLC + 0 + 4 + + + + + RDL1R + RDL1R + mailbox data high register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + DATA3 + DATA3 + 24 + 8 + + + DATA2 + DATA2 + 16 + 8 + + + DATA1 + DATA1 + 8 + 8 + + + DATA0 + DATA0 + 0 + 8 + + + + + RDH1R + RDH1R + mailbox data high register + 0x1CC + 0x20 + read-only + 0x00000000 + + + DATA7 + DATA7 + 24 + 8 + + + DATA6 + DATA6 + 16 + 8 + + + DATA5 + DATA5 + 8 + 8 + + + DATA4 + DATA4 + 0 + 8 + + + + + FMR + FMR + filter master register + 0x200 + 0x20 + read-write + 0x2A1C0E01 + + + CAN2SB + CAN2SB + 8 + 6 + + + FINIT + FINIT + 0 + 1 + + + + + FM1R + FM1R + filter mode register + 0x204 + 0x20 + read-write + 0x00000000 + + + FBM0 + Filter mode + 0 + 1 + + + FBM1 + Filter mode + 1 + 1 + + + FBM2 + Filter mode + 2 + 1 + + + FBM3 + Filter mode + 3 + 1 + + + FBM4 + Filter mode + 4 + 1 + + + FBM5 + Filter mode + 5 + 1 + + + FBM6 + Filter mode + 6 + 1 + + + FBM7 + Filter mode + 7 + 1 + + + FBM8 + Filter mode + 8 + 1 + + + FBM9 + Filter mode + 9 + 1 + + + FBM10 + Filter mode + 10 + 1 + + + FBM11 + Filter mode + 11 + 1 + + + FBM12 + Filter mode + 12 + 1 + + + FBM13 + Filter mode + 13 + 1 + + + FBM14 + Filter mode + 14 + 1 + + + FBM15 + Filter mode + 15 + 1 + + + FBM16 + Filter mode + 16 + 1 + + + FBM17 + Filter mode + 17 + 1 + + + FBM18 + Filter mode + 18 + 1 + + + FBM19 + Filter mode + 19 + 1 + + + FBM20 + Filter mode + 20 + 1 + + + FBM21 + Filter mode + 21 + 1 + + + FBM22 + Filter mode + 22 + 1 + + + FBM23 + Filter mode + 23 + 1 + + + FBM24 + Filter mode + 24 + 1 + + + FBM25 + Filter mode + 25 + 1 + + + FBM26 + Filter mode + 26 + 1 + + + FBM27 + Filter mode + 27 + 1 + + + + + FS1R + FS1R + filter scale register + 0x20C + 0x20 + read-write + 0x00000000 + + + FSC0 + Filter scale configuration + 0 + 1 + + + FSC1 + Filter scale configuration + 1 + 1 + + + FSC2 + Filter scale configuration + 2 + 1 + + + FSC3 + Filter scale configuration + 3 + 1 + + + FSC4 + Filter scale configuration + 4 + 1 + + + FSC5 + Filter scale configuration + 5 + 1 + + + FSC6 + Filter scale configuration + 6 + 1 + + + FSC7 + Filter scale configuration + 7 + 1 + + + FSC8 + Filter scale configuration + 8 + 1 + + + FSC9 + Filter scale configuration + 9 + 1 + + + FSC10 + Filter scale configuration + 10 + 1 + + + FSC11 + Filter scale configuration + 11 + 1 + + + FSC12 + Filter scale configuration + 12 + 1 + + + FSC13 + Filter scale configuration + 13 + 1 + + + FSC14 + Filter scale configuration + 14 + 1 + + + FSC15 + Filter scale configuration + 15 + 1 + + + FSC16 + Filter scale configuration + 16 + 1 + + + FSC17 + Filter scale configuration + 17 + 1 + + + FSC18 + Filter scale configuration + 18 + 1 + + + FSC19 + Filter scale configuration + 19 + 1 + + + FSC20 + Filter scale configuration + 20 + 1 + + + FSC21 + Filter scale configuration + 21 + 1 + + + FSC22 + Filter scale configuration + 22 + 1 + + + FSC23 + Filter scale configuration + 23 + 1 + + + FSC24 + Filter scale configuration + 24 + 1 + + + FSC25 + Filter scale configuration + 25 + 1 + + + FSC26 + Filter scale configuration + 26 + 1 + + + FSC27 + Filter scale configuration + 27 + 1 + + + + + FFA1R + FFA1R + filter FIFO assignment + register + 0x214 + 0x20 + read-write + 0x00000000 + + + FFA0 + Filter FIFO assignment for filter + 0 + 0 + 1 + + + FFA1 + Filter FIFO assignment for filter + 1 + 1 + 1 + + + FFA2 + Filter FIFO assignment for filter + 2 + 2 + 1 + + + FFA3 + Filter FIFO assignment for filter + 3 + 3 + 1 + + + FFA4 + Filter FIFO assignment for filter + 4 + 4 + 1 + + + FFA5 + Filter FIFO assignment for filter + 5 + 5 + 1 + + + FFA6 + Filter FIFO assignment for filter + 6 + 6 + 1 + + + FFA7 + Filter FIFO assignment for filter + 7 + 7 + 1 + + + FFA8 + Filter FIFO assignment for filter + 8 + 8 + 1 + + + FFA9 + Filter FIFO assignment for filter + 9 + 9 + 1 + + + FFA10 + Filter FIFO assignment for filter + 10 + 10 + 1 + + + FFA11 + Filter FIFO assignment for filter + 11 + 11 + 1 + + + FFA12 + Filter FIFO assignment for filter + 12 + 12 + 1 + + + FFA13 + Filter FIFO assignment for filter + 13 + 13 + 1 + + + FFA14 + Filter FIFO assignment for filter + 14 + 14 + 1 + + + FFA15 + Filter FIFO assignment for filter + 15 + 15 + 1 + + + FFA16 + Filter FIFO assignment for filter + 16 + 16 + 1 + + + FFA17 + Filter FIFO assignment for filter + 17 + 17 + 1 + + + FFA18 + Filter FIFO assignment for filter + 18 + 18 + 1 + + + FFA19 + Filter FIFO assignment for filter + 19 + 19 + 1 + + + FFA20 + Filter FIFO assignment for filter + 20 + 20 + 1 + + + FFA21 + Filter FIFO assignment for filter + 21 + 21 + 1 + + + FFA22 + Filter FIFO assignment for filter + 22 + 22 + 1 + + + FFA23 + Filter FIFO assignment for filter + 23 + 23 + 1 + + + FFA24 + Filter FIFO assignment for filter + 24 + 24 + 1 + + + FFA25 + Filter FIFO assignment for filter + 25 + 25 + 1 + + + FFA26 + Filter FIFO assignment for filter + 26 + 26 + 1 + + + FFA27 + Filter FIFO assignment for filter + 27 + 27 + 1 + + + + + FA1R + FA1R + filter activation register + 0x21C + 0x20 + read-write + 0x00000000 + + + FACT0 + Filter active + 0 + 1 + + + FACT1 + Filter active + 1 + 1 + + + FACT2 + Filter active + 2 + 1 + + + FACT3 + Filter active + 3 + 1 + + + FACT4 + Filter active + 4 + 1 + + + FACT5 + Filter active + 5 + 1 + + + FACT6 + Filter active + 6 + 1 + + + FACT7 + Filter active + 7 + 1 + + + FACT8 + Filter active + 8 + 1 + + + FACT9 + Filter active + 9 + 1 + + + FACT10 + Filter active + 10 + 1 + + + FACT11 + Filter active + 11 + 1 + + + FACT12 + Filter active + 12 + 1 + + + FACT13 + Filter active + 13 + 1 + + + FACT14 + Filter active + 14 + 1 + + + FACT15 + Filter active + 15 + 1 + + + FACT16 + Filter active + 16 + 1 + + + FACT17 + Filter active + 17 + 1 + + + FACT18 + Filter active + 18 + 1 + + + FACT19 + Filter active + 19 + 1 + + + FACT20 + Filter active + 20 + 1 + + + FACT21 + Filter active + 21 + 1 + + + FACT22 + Filter active + 22 + 1 + + + FACT23 + Filter active + 23 + 1 + + + FACT24 + Filter active + 24 + 1 + + + FACT25 + Filter active + 25 + 1 + + + FACT26 + Filter active + 26 + 1 + + + FACT27 + Filter active + 27 + 1 + + + + + F0R1 + F0R1 + Filter bank 0 register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F0R2 + F0R2 + Filter bank 0 register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R1 + F1R1 + Filter bank 1 register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F1R2 + F1R2 + Filter bank 1 register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R1 + F2R1 + Filter bank 2 register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F2R2 + F2R2 + Filter bank 2 register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R1 + F3R1 + Filter bank 3 register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F3R2 + F3R2 + Filter bank 3 register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R1 + F4R1 + Filter bank 4 register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F4R2 + F4R2 + Filter bank 4 register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R1 + F5R1 + Filter bank 5 register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F5R2 + F5R2 + Filter bank 5 register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R1 + F6R1 + Filter bank 6 register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F6R2 + F6R2 + Filter bank 6 register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R1 + F7R1 + Filter bank 7 register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F7R2 + F7R2 + Filter bank 7 register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R1 + F8R1 + Filter bank 8 register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F8R2 + F8R2 + Filter bank 8 register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R1 + F9R1 + Filter bank 9 register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F9R2 + F9R2 + Filter bank 9 register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R1 + F10R1 + Filter bank 10 register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F10R2 + F10R2 + Filter bank 10 register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R1 + F11R1 + Filter bank 11 register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F11R2 + F11R2 + Filter bank 11 register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R1 + F12R1 + Filter bank 4 register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F12R2 + F12R2 + Filter bank 12 register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R1 + F13R1 + Filter bank 13 register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F13R2 + F13R2 + Filter bank 13 register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R1 + F14R1 + Filter bank 14 register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F14R2 + F14R2 + Filter bank 14 register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R1 + F15R1 + Filter bank 15 register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F15R2 + F15R2 + Filter bank 15 register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R1 + F16R1 + Filter bank 16 register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F16R2 + F16R2 + Filter bank 16 register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R1 + F17R1 + Filter bank 17 register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F17R2 + F17R2 + Filter bank 17 register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R1 + F18R1 + Filter bank 18 register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F18R2 + F18R2 + Filter bank 18 register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R1 + F19R1 + Filter bank 19 register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F19R2 + F19R2 + Filter bank 19 register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R1 + F20R1 + Filter bank 20 register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F20R2 + F20R2 + Filter bank 20 register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R1 + F21R1 + Filter bank 21 register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F21R2 + F21R2 + Filter bank 21 register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R1 + F22R1 + Filter bank 22 register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F22R2 + F22R2 + Filter bank 22 register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R1 + F23R1 + Filter bank 23 register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F23R2 + F23R2 + Filter bank 23 register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R1 + F24R1 + Filter bank 24 register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F24R2 + F24R2 + Filter bank 24 register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R1 + F25R1 + Filter bank 25 register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F25R2 + F25R2 + Filter bank 25 register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R1 + F26R1 + Filter bank 26 register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F26R2 + F26R2 + Filter bank 26 register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R1 + F27R1 + Filter bank 27 register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + F27R2 + F27R2 + Filter bank 27 register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FB0 + Filter bits + 0 + 1 + + + FB1 + Filter bits + 1 + 1 + + + FB2 + Filter bits + 2 + 1 + + + FB3 + Filter bits + 3 + 1 + + + FB4 + Filter bits + 4 + 1 + + + FB5 + Filter bits + 5 + 1 + + + FB6 + Filter bits + 6 + 1 + + + FB7 + Filter bits + 7 + 1 + + + FB8 + Filter bits + 8 + 1 + + + FB9 + Filter bits + 9 + 1 + + + FB10 + Filter bits + 10 + 1 + + + FB11 + Filter bits + 11 + 1 + + + FB12 + Filter bits + 12 + 1 + + + FB13 + Filter bits + 13 + 1 + + + FB14 + Filter bits + 14 + 1 + + + FB15 + Filter bits + 15 + 1 + + + FB16 + Filter bits + 16 + 1 + + + FB17 + Filter bits + 17 + 1 + + + FB18 + Filter bits + 18 + 1 + + + FB19 + Filter bits + 19 + 1 + + + FB20 + Filter bits + 20 + 1 + + + FB21 + Filter bits + 21 + 1 + + + FB22 + Filter bits + 22 + 1 + + + FB23 + Filter bits + 23 + 1 + + + FB24 + Filter bits + 24 + 1 + + + FB25 + Filter bits + 25 + 1 + + + FB26 + Filter bits + 26 + 1 + + + FB27 + Filter bits + 27 + 1 + + + FB28 + Filter bits + 28 + 1 + + + FB29 + Filter bits + 29 + 1 + + + FB30 + Filter bits + 30 + 1 + + + FB31 + Filter bits + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupts + 63 + + + CAN2_RX0 + CAN2 RX0 interrupts + 64 + + + CAN2_RX1 + CAN2 RX1 interrupts + 65 + + + CAN2_SCE + CAN2 SCE interrupt + 66 + + + + FLASH + FLASH + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + ACR + ACR + Flash access control register + 0x0 + 0x20 + read-write + 0x00000000 + + + LATENCY + Latency + 0 + 4 + + + PRFTEN + Prefetch enable + 8 + 1 + + + ARTEN + ART Accelerator Enable + 9 + 1 + + + ARTRST + ART Accelerator reset + 11 + 1 + + + + + KEYR + KEYR + Flash key register + 0x4 + 0x20 + write-only + 0x00000000 + + + KEY + FPEC key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + Flash option key register + 0x8 + 0x20 + write-only + 0x00000000 + + + OPTKEY + Option byte key + 0 + 32 + + + + + SR + SR + Status register + 0xC + 0x20 + 0x00000000 + + + EOP + End of operation + 0 + 1 + read-write + + + OPERR + Operation error + 1 + 1 + read-write + + + WRPERR + Write protection error + 4 + 1 + read-write + + + PGAERR + Programming alignment + error + 5 + 1 + read-write + + + PGPERR + Programming parallelism + error + 6 + 1 + read-write + + + PGSERR + Programming sequence error + 7 + 1 + read-write + + + BSY + Busy + 16 + 1 + read-only + + + + + CR + CR + Control register + 0x10 + 0x20 + read-write + 0x80000000 + + + PG + Programming + 0 + 1 + + + SER + Sector Erase + 1 + 1 + + + MER + Mass Erase of sectors 0 to + 11 + 2 + 1 + + + SNB + Sector number + 3 + 5 + + + PSIZE + Program size + 8 + 2 + + + MER1 + Mass Erase of sectors 12 to + 23 + 15 + 1 + + + STRT + Start + 16 + 1 + + + EOPIE + End of operation interrupt + enable + 24 + 1 + + + ERRIE + Error interrupt enable + 25 + 1 + + + LOCK + Lock + 31 + 1 + + + + + OPTCR + OPTCR + Flash option control register + 0x14 + 0x20 + read-write + 0x0FFFAAED + + + OPTLOCK + Option lock + 0 + 1 + + + OPTSTRT + Option start + 1 + 1 + + + BOR_LEV + BOR reset Level + 2 + 2 + + + WWDG_SW + User option bytes + 4 + 1 + + + IWDG_SW + User option bytes + 5 + 1 + + + nRST_STOP + User option bytes + 6 + 1 + + + nRST_STDBY + User option bytes + 7 + 1 + + + RDP + Read protect + 8 + 8 + + + nWRP + Not write protect + 16 + 8 + + + IWDG_STDBY + Independent watchdog counter freeze in + standby mode + 30 + 1 + + + IWDG_STOP + Independent watchdog counter freeze in + Stop mode + 31 + 1 + + + + + OPTCR1 + OPTCR1 + Flash option control register + 1 + 0x18 + 0x20 + read-write + 0x0FFF0000 + + + BOOT_ADD0 + Boot base address when Boot pin + =0 + 0 + 16 + + + BOOT_ADD1 + Boot base address when Boot pin + =1 + 16 + 16 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x40013C00 + + 0x0 + 0x400 + registers + + + TAMP_STAMP + Tamper and TimeStamp interrupts through the + EXTI line + 2 + + + EXTI0 + EXTI Line0 interrupt + 6 + + + EXTI1 + EXTI Line1 interrupt + 7 + + + EXTI2 + EXTI Line2 interrupt + 8 + + + EXTI3 + EXTI Line3 interrupt + 9 + + + EXTI4 + EXTI Line4 interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + + IMR + IMR + Interrupt mask register + (EXTI_IMR) + 0x0 + 0x20 + read-write + 0x00000000 + + + MR0 + Interrupt Mask on line 0 + 0 + 1 + + + MR1 + Interrupt Mask on line 1 + 1 + 1 + + + MR2 + Interrupt Mask on line 2 + 2 + 1 + + + MR3 + Interrupt Mask on line 3 + 3 + 1 + + + MR4 + Interrupt Mask on line 4 + 4 + 1 + + + MR5 + Interrupt Mask on line 5 + 5 + 1 + + + MR6 + Interrupt Mask on line 6 + 6 + 1 + + + MR7 + Interrupt Mask on line 7 + 7 + 1 + + + MR8 + Interrupt Mask on line 8 + 8 + 1 + + + MR9 + Interrupt Mask on line 9 + 9 + 1 + + + MR10 + Interrupt Mask on line 10 + 10 + 1 + + + MR11 + Interrupt Mask on line 11 + 11 + 1 + + + MR12 + Interrupt Mask on line 12 + 12 + 1 + + + MR13 + Interrupt Mask on line 13 + 13 + 1 + + + MR14 + Interrupt Mask on line 14 + 14 + 1 + + + MR15 + Interrupt Mask on line 15 + 15 + 1 + + + MR16 + Interrupt Mask on line 16 + 16 + 1 + + + MR17 + Interrupt Mask on line 17 + 17 + 1 + + + MR18 + Interrupt Mask on line 18 + 18 + 1 + + + MR19 + Interrupt Mask on line 19 + 19 + 1 + + + MR20 + Interrupt Mask on line 20 + 20 + 1 + + + MR21 + Interrupt Mask on line 21 + 21 + 1 + + + MR22 + Interrupt Mask on line 22 + 22 + 1 + + + + + EMR + EMR + Event mask register (EXTI_EMR) + 0x4 + 0x20 + read-write + 0x00000000 + + + MR0 + Event Mask on line 0 + 0 + 1 + + + MR1 + Event Mask on line 1 + 1 + 1 + + + MR2 + Event Mask on line 2 + 2 + 1 + + + MR3 + Event Mask on line 3 + 3 + 1 + + + MR4 + Event Mask on line 4 + 4 + 1 + + + MR5 + Event Mask on line 5 + 5 + 1 + + + MR6 + Event Mask on line 6 + 6 + 1 + + + MR7 + Event Mask on line 7 + 7 + 1 + + + MR8 + Event Mask on line 8 + 8 + 1 + + + MR9 + Event Mask on line 9 + 9 + 1 + + + MR10 + Event Mask on line 10 + 10 + 1 + + + MR11 + Event Mask on line 11 + 11 + 1 + + + MR12 + Event Mask on line 12 + 12 + 1 + + + MR13 + Event Mask on line 13 + 13 + 1 + + + MR14 + Event Mask on line 14 + 14 + 1 + + + MR15 + Event Mask on line 15 + 15 + 1 + + + MR16 + Event Mask on line 16 + 16 + 1 + + + MR17 + Event Mask on line 17 + 17 + 1 + + + MR18 + Event Mask on line 18 + 18 + 1 + + + MR19 + Event Mask on line 19 + 19 + 1 + + + MR20 + Event Mask on line 20 + 20 + 1 + + + MR21 + Event Mask on line 21 + 21 + 1 + + + MR22 + Event Mask on line 22 + 22 + 1 + + + + + RTSR + RTSR + Rising Trigger selection register + (EXTI_RTSR) + 0x8 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Rising trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Rising trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Rising trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Rising trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Rising trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Rising trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Rising trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Rising trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Rising trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Rising trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Rising trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Rising trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Rising trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Rising trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Rising trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Rising trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Rising trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Rising trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Rising trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Rising trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Rising trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Rising trigger event configuration of + line 22 + 22 + 1 + + + + + FTSR + FTSR + Falling Trigger selection register + (EXTI_FTSR) + 0xC + 0x20 + read-write + 0x00000000 + + + TR0 + Falling trigger event configuration of + line 0 + 0 + 1 + + + TR1 + Falling trigger event configuration of + line 1 + 1 + 1 + + + TR2 + Falling trigger event configuration of + line 2 + 2 + 1 + + + TR3 + Falling trigger event configuration of + line 3 + 3 + 1 + + + TR4 + Falling trigger event configuration of + line 4 + 4 + 1 + + + TR5 + Falling trigger event configuration of + line 5 + 5 + 1 + + + TR6 + Falling trigger event configuration of + line 6 + 6 + 1 + + + TR7 + Falling trigger event configuration of + line 7 + 7 + 1 + + + TR8 + Falling trigger event configuration of + line 8 + 8 + 1 + + + TR9 + Falling trigger event configuration of + line 9 + 9 + 1 + + + TR10 + Falling trigger event configuration of + line 10 + 10 + 1 + + + TR11 + Falling trigger event configuration of + line 11 + 11 + 1 + + + TR12 + Falling trigger event configuration of + line 12 + 12 + 1 + + + TR13 + Falling trigger event configuration of + line 13 + 13 + 1 + + + TR14 + Falling trigger event configuration of + line 14 + 14 + 1 + + + TR15 + Falling trigger event configuration of + line 15 + 15 + 1 + + + TR16 + Falling trigger event configuration of + line 16 + 16 + 1 + + + TR17 + Falling trigger event configuration of + line 17 + 17 + 1 + + + TR18 + Falling trigger event configuration of + line 18 + 18 + 1 + + + TR19 + Falling trigger event configuration of + line 19 + 19 + 1 + + + TR20 + Falling trigger event configuration of + line 20 + 20 + 1 + + + TR21 + Falling trigger event configuration of + line 21 + 21 + 1 + + + TR22 + Falling trigger event configuration of + line 22 + 22 + 1 + + + + + SWIER + SWIER + Software interrupt event register + (EXTI_SWIER) + 0x10 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Software Interrupt on line + 0 + 0 + 1 + + + SWIER1 + Software Interrupt on line + 1 + 1 + 1 + + + SWIER2 + Software Interrupt on line + 2 + 2 + 1 + + + SWIER3 + Software Interrupt on line + 3 + 3 + 1 + + + SWIER4 + Software Interrupt on line + 4 + 4 + 1 + + + SWIER5 + Software Interrupt on line + 5 + 5 + 1 + + + SWIER6 + Software Interrupt on line + 6 + 6 + 1 + + + SWIER7 + Software Interrupt on line + 7 + 7 + 1 + + + SWIER8 + Software Interrupt on line + 8 + 8 + 1 + + + SWIER9 + Software Interrupt on line + 9 + 9 + 1 + + + SWIER10 + Software Interrupt on line + 10 + 10 + 1 + + + SWIER11 + Software Interrupt on line + 11 + 11 + 1 + + + SWIER12 + Software Interrupt on line + 12 + 12 + 1 + + + SWIER13 + Software Interrupt on line + 13 + 13 + 1 + + + SWIER14 + Software Interrupt on line + 14 + 14 + 1 + + + SWIER15 + Software Interrupt on line + 15 + 15 + 1 + + + SWIER16 + Software Interrupt on line + 16 + 16 + 1 + + + SWIER17 + Software Interrupt on line + 17 + 17 + 1 + + + SWIER18 + Software Interrupt on line + 18 + 18 + 1 + + + SWIER19 + Software Interrupt on line + 19 + 19 + 1 + + + SWIER20 + Software Interrupt on line + 20 + 20 + 1 + + + SWIER21 + Software Interrupt on line + 21 + 21 + 1 + + + SWIER22 + Software Interrupt on line + 22 + 22 + 1 + + + + + PR + PR + Pending register (EXTI_PR) + 0x14 + 0x20 + read-write + 0x00000000 + + + PR0 + Pending bit 0 + 0 + 1 + + + PR1 + Pending bit 1 + 1 + 1 + + + PR2 + Pending bit 2 + 2 + 1 + + + PR3 + Pending bit 3 + 3 + 1 + + + PR4 + Pending bit 4 + 4 + 1 + + + PR5 + Pending bit 5 + 5 + 1 + + + PR6 + Pending bit 6 + 6 + 1 + + + PR7 + Pending bit 7 + 7 + 1 + + + PR8 + Pending bit 8 + 8 + 1 + + + PR9 + Pending bit 9 + 9 + 1 + + + PR10 + Pending bit 10 + 10 + 1 + + + PR11 + Pending bit 11 + 11 + 1 + + + PR12 + Pending bit 12 + 12 + 1 + + + PR13 + Pending bit 13 + 13 + 1 + + + PR14 + Pending bit 14 + 14 + 1 + + + PR15 + Pending bit 15 + 15 + 1 + + + PR16 + Pending bit 16 + 16 + 1 + + + PR17 + Pending bit 17 + 17 + 1 + + + PR18 + Pending bit 18 + 18 + 1 + + + PR19 + Pending bit 19 + 19 + 1 + + + PR20 + Pending bit 20 + 20 + 1 + + + PR21 + Pending bit 21 + 21 + 1 + + + PR22 + Pending bit 22 + 22 + 1 + + + + + + + LTDC + LCD-TFT Controller + LTDC + 0x40016800 + + 0x0 + 0x400 + registers + + + LCD_TFT + LTDC global interrupt + 88 + + + LTDC_ER + LTDC Error global interrupt + 89 + + + + SSCR + SSCR + Synchronization Size Configuration + Register + 0x8 + 0x20 + read-write + 0x00000000 + + + HSW + Horizontal Synchronization Width (in + units of pixel clock period) + 16 + 10 + + + VSH + Vertical Synchronization Height (in + units of horizontal scan line) + 0 + 11 + + + + + BPCR + BPCR + Back Porch Configuration + Register + 0xC + 0x20 + read-write + 0x00000000 + + + AHBP + Accumulated Horizontal back porch (in + units of pixel clock period) + 16 + 10 + + + AVBP + Accumulated Vertical back porch (in + units of horizontal scan line) + 0 + 11 + + + + + AWCR + AWCR + Active Width Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + AAV + AAV + 16 + 10 + + + AAH + Accumulated Active Height (in units of + horizontal scan line) + 0 + 11 + + + + + TWCR + TWCR + Total Width Configuration + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTALW + Total Width (in units of pixel clock + period) + 16 + 10 + + + TOTALH + Total Height (in units of horizontal + scan line) + 0 + 11 + + + + + GCR + GCR + Global Control Register + 0x18 + 0x20 + 0x00002220 + + + HSPOL + Horizontal Synchronization + Polarity + 31 + 1 + read-write + + + VSPOL + Vertical Synchronization + Polarity + 30 + 1 + read-write + + + DEPOL + Data Enable Polarity + 29 + 1 + read-write + + + PCPOL + Pixel Clock Polarity + 28 + 1 + read-write + + + DEN + Dither Enable + 16 + 1 + read-write + + + DRW + Dither Red Width + 12 + 3 + read-only + + + DGW + Dither Green Width + 8 + 3 + read-only + + + DBW + Dither Blue Width + 4 + 3 + read-only + + + LTDCEN + LCD-TFT controller enable + bit + 0 + 1 + read-write + + + + + SRCR + SRCR + Shadow Reload Configuration + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + VBR + Vertical Blanking Reload + 1 + 1 + + + IMR + Immediate Reload + 0 + 1 + + + + + BCCR + BCCR + Background Color Configuration + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BC + Background Color Red value + 0 + 24 + + + + + IER + IER + Interrupt Enable Register + 0x34 + 0x20 + read-write + 0x00000000 + + + RRIE + Register Reload interrupt + enable + 3 + 1 + + + TERRIE + Transfer Error Interrupt + Enable + 2 + 1 + + + FUIE + FIFO Underrun Interrupt + Enable + 1 + 1 + + + LIE + Line Interrupt Enable + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x38 + 0x20 + read-only + 0x00000000 + + + RRIF + Register Reload Interrupt + Flag + 3 + 1 + + + TERRIF + Transfer Error interrupt + flag + 2 + 1 + + + FUIF + FIFO Underrun Interrupt + flag + 1 + 1 + + + LIF + Line Interrupt flag + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x3C + 0x20 + write-only + 0x00000000 + + + CRRIF + Clears Register Reload Interrupt + Flag + 3 + 1 + + + CTERRIF + Clears the Transfer Error Interrupt + Flag + 2 + 1 + + + CFUIF + Clears the FIFO Underrun Interrupt + flag + 1 + 1 + + + CLIF + Clears the Line Interrupt + Flag + 0 + 1 + + + + + LIPCR + LIPCR + Line Interrupt Position Configuration + Register + 0x40 + 0x20 + read-write + 0x00000000 + + + LIPOS + Line Interrupt Position + 0 + 11 + + + + + CPSR + CPSR + Current Position Status + Register + 0x44 + 0x20 + read-only + 0x00000000 + + + CXPOS + Current X Position + 16 + 16 + + + CYPOS + Current Y Position + 0 + 16 + + + + + CDSR + CDSR + Current Display Status + Register + 0x48 + 0x20 + read-only + 0x0000000F + + + HSYNCS + Horizontal Synchronization display + Status + 3 + 1 + + + VSYNCS + Vertical Synchronization display + Status + 2 + 1 + + + HDES + Horizontal Data Enable display + Status + 1 + 1 + + + VDES + Vertical Data Enable display + Status + 0 + 1 + + + + + L1CR + L1CR + Layerx Control Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L1WHPCR + L1WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x88 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L1WVPCR + L1WVPCR + Layerx Window Vertical Position + Configuration Register + 0x8C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L1CKCR + L1CKCR + Layerx Color Keying Configuration + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L1PFCR + L1PFCR + Layerx Pixel Format Configuration + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L1CACR + L1CACR + Layerx Constant Alpha Configuration + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L1DCCR + L1DCCR + Layerx Default Color Configuration + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L1BFCR + L1BFCR + Layerx Blending Factors Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L1CFBAR + L1CFBAR + Layerx Color Frame Buffer Address + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L1CFBLR + L1CFBLR + Layerx Color Frame Buffer Length + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L1CFBLNR + L1CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L1CLUTWR + L1CLUTWR + Layerx CLUT Write Register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + L2CR + L2CR + Layerx Control Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L2WHPCR + L2WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x108 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L2WVPCR + L2WVPCR + Layerx Window Vertical Position + Configuration Register + 0x10C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L2CKCR + L2CKCR + Layerx Color Keying Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 15 + 9 + + + CKGREEN + Color Key Green value + 8 + 7 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L2PFCR + L2PFCR + Layerx Pixel Format Configuration + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L2CACR + L2CACR + Layerx Constant Alpha Configuration + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L2DCCR + L2DCCR + Layerx Default Color Configuration + Register + 0x11C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L2BFCR + L2BFCR + Layerx Blending Factors Configuration + Register + 0x120 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L2CFBAR + L2CFBAR + Layerx Color Frame Buffer Address + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L2CFBLR + L2CFBLR + Layerx Color Frame Buffer Length + Register + 0x130 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L2CFBLNR + L2CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0x134 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L2CLUTWR + L2CLUTWR + Layerx CLUT Write Register + 0x144 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + + + SAI1 + Serial audio interface + SAI + 0x40015800 + + 0x0 + 0x400 + registers + + + SAI1 + SAI1 global interrupt + 87 + + + + BCR1 + BCR1 + BConfiguration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIBEN + Audio block B enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + BCR2 + BCR2 + BConfiguration register 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + BFRCR + BFRCR + BFRCR + 0x2C + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + BSLOTR + BSLOTR + BSlot register + 0x30 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + BIM + BIM + BInterrupt mask register2 + 0x34 + 0x20 + read-write + 0x00000000 + + + LFSDETIE + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + BSR + BSR + BStatus register + 0x38 + 0x20 + read-only + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + BCLRFR + BCLRFR + BClear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + BDR + BDR + BData register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + ACR1 + ACR1 + AConfiguration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MCJDIV + Master clock divider + 20 + 4 + + + NODIV + No divider + 19 + 1 + + + DMAEN + DMA enable + 17 + 1 + + + SAIAEN + Audio block A enable + 16 + 1 + + + OutDri + Output drive + 13 + 1 + + + MONO + Mono mode + 12 + 1 + + + SYNCEN + Synchronization enable + 10 + 2 + + + CKSTR + Clock strobing edge + 9 + 1 + + + LSBFIRST + Least significant bit + first + 8 + 1 + + + DS + Data size + 5 + 3 + + + PRTCFG + Protocol configuration + 2 + 2 + + + MODE + Audio block mode + 0 + 2 + + + + + ACR2 + ACR2 + AConfiguration register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + COMP + Companding mode + 14 + 2 + + + CPL + Complement bit + 13 + 1 + + + MUTECN + Mute counter + 7 + 6 + + + MUTEVAL + Mute value + 6 + 1 + + + MUTE + Mute + 5 + 1 + + + TRIS + Tristate management on data + line + 4 + 1 + + + FFLUS + FIFO flush + 3 + 1 + + + FTH + FIFO threshold + 0 + 3 + + + + + AFRCR + AFRCR + AFRCR + 0xC + 0x20 + read-write + 0x00000007 + + + FSOFF + Frame synchronization + offset + 18 + 1 + + + FSPOL + Frame synchronization + polarity + 17 + 1 + + + FSDEF + Frame synchronization + definition + 16 + 1 + + + FSALL + Frame synchronization active level + length + 8 + 7 + + + FRL + Frame length + 0 + 8 + + + + + ASLOTR + ASLOTR + ASlot register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLOTEN + Slot enable + 16 + 16 + + + NBSLOT + Number of slots in an audio + frame + 8 + 4 + + + SLOTSZ + Slot size + 6 + 2 + + + FBOFF + First bit offset + 0 + 5 + + + + + AIM + AIM + AInterrupt mask register2 + 0x14 + 0x20 + read-write + 0x00000000 + + + LFSDET + Late frame synchronization detection + interrupt enable + 6 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable + 5 + 1 + + + CNRDYIE + Codec not ready interrupt + enable + 4 + 1 + + + FREQIE + FIFO request interrupt + enable + 3 + 1 + + + WCKCFG + Wrong clock configuration interrupt + enable + 2 + 1 + + + MUTEDET + Mute detection interrupt + enable + 1 + 1 + + + OVRUDRIE + Overrun/underrun interrupt + enable + 0 + 1 + + + + + ASR + ASR + AStatus register + 0x18 + 0x20 + read-write + 0x00000000 + + + FLVL + FIFO level threshold + 16 + 3 + + + LFSDET + Late frame synchronization + detection + 6 + 1 + + + AFSDET + Anticipated frame synchronization + detection + 5 + 1 + + + CNRDY + Codec not ready + 4 + 1 + + + FREQ + FIFO request + 3 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. + 2 + 1 + + + MUTEDET + Mute detection + 1 + 1 + + + OVRUDR + Overrun / underrun + 0 + 1 + + + + + ACLRFR + ACLRFR + AClear flag register + 0x1C + 0x20 + read-write + 0x00000000 + + + LFSDET + Clear late frame synchronization + detection flag + 6 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. + 5 + 1 + + + CNRDY + Clear codec not ready flag + 4 + 1 + + + WCKCFG + Clear wrong clock configuration + flag + 2 + 1 + + + MUTEDET + Mute detection flag + 1 + 1 + + + OVRUDR + Clear overrun / underrun + 0 + 1 + + + + + ADR + ADR + AData register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + GCR + GCR + Global configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + SYNCIN + Synchronization inputs + 0 + 2 + + + SYNCOUT + Synchronization outputs + 4 + 2 + + + + + + + SAI2 + 0x40015C00 + + + DMA2D + DMA2D controller + DMA2D + 0x4002B000 + + 0x0 + 0xC00 + registers + + + DMA2D + DMA2D global interrupt + 90 + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + MODE + DMA2D mode + 16 + 2 + + + CEIE + Configuration Error Interrupt + Enable + 13 + 1 + + + CTCIE + CLUT transfer complete interrupt + enable + 12 + 1 + + + CAEIE + CLUT access error interrupt + enable + 11 + 1 + + + TWIE + Transfer watermark interrupt + enable + 10 + 1 + + + TCIE + Transfer complete interrupt + enable + 9 + 1 + + + TEIE + Transfer error interrupt + enable + 8 + 1 + + + ABORT + Abort + 2 + 1 + + + SUSP + Suspend + 1 + 1 + + + START + Start + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x4 + 0x20 + read-only + 0x00000000 + + + CEIF + Configuration error interrupt + flag + 5 + 1 + + + CTCIF + CLUT transfer complete interrupt + flag + 4 + 1 + + + CAEIF + CLUT access error interrupt + flag + 3 + 1 + + + TWIF + Transfer watermark interrupt + flag + 2 + 1 + + + TCIF + Transfer complete interrupt + flag + 1 + 1 + + + TEIF + Transfer error interrupt + flag + 0 + 1 + + + + + IFCR + IFCR + interrupt flag clear register + 0x8 + 0x20 + read-write + 0x00000000 + + + CCEIF + Clear configuration error interrupt + flag + 5 + 1 + + + CCTCIF + Clear CLUT transfer complete interrupt + flag + 4 + 1 + + + CAECIF + Clear CLUT access error interrupt + flag + 3 + 1 + + + CTWIF + Clear transfer watermark interrupt + flag + 2 + 1 + + + CTCIF + Clear transfer complete interrupt + flag + 1 + 1 + + + CTEIF + Clear Transfer error interrupt + flag + 0 + 1 + + + + + FGMAR + FGMAR + foreground memory address + register + 0xC + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + FGOR + FGOR + foreground offset register + 0x10 + 0x20 + read-write + 0x00000000 + + + LO + Line offset + 0 + 14 + + + + + BGMAR + BGMAR + background memory address + register + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + BGOR + BGOR + background offset register + 0x18 + 0x20 + read-write + 0x00000000 + + + LO + Line offset + 0 + 14 + + + + + FGPFCCR + FGPFCCR + foreground PFC control + register + 0x1C + 0x20 + read-write + 0x00000000 + + + ALPHA + Alpha value + 24 + 8 + + + AM + Alpha mode + 16 + 2 + + + CS + CLUT size + 8 + 8 + + + START + Start + 5 + 1 + + + CCM + CLUT color mode + 4 + 1 + + + CM + Color mode + 0 + 4 + + + + + FGCOLR + FGCOLR + foreground color register + 0x20 + 0x20 + read-write + 0x00000000 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + BGPFCCR + BGPFCCR + background PFC control + register + 0x24 + 0x20 + read-write + 0x00000000 + + + ALPHA + Alpha value + 24 + 8 + + + AM + Alpha mode + 16 + 2 + + + CS + CLUT size + 8 + 8 + + + START + Start + 5 + 1 + + + CCM + CLUT Color mode + 4 + 1 + + + CM + Color mode + 0 + 4 + + + + + BGCOLR + BGCOLR + background color register + 0x28 + 0x20 + read-write + 0x00000000 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + FGCMAR + FGCMAR + foreground CLUT memory address + register + 0x2C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address + 0 + 32 + + + + + BGCMAR + BGCMAR + background CLUT memory address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + MA + Memory address + 0 + 32 + + + + + OPFCCR + OPFCCR + output PFC control register + 0x34 + 0x20 + read-write + 0x00000000 + + + CM + Color mode + 0 + 3 + + + + + OCOLR + OCOLR + output color register + 0x38 + 0x20 + read-write + 0x00000000 + + + APLHA + Alpha Channel Value + 24 + 8 + + + RED + Red Value + 16 + 8 + + + GREEN + Green Value + 8 + 8 + + + BLUE + Blue Value + 0 + 8 + + + + + OMAR + OMAR + output memory address register + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address + 0 + 32 + + + + + OOR + OOR + output offset register + 0x40 + 0x20 + read-write + 0x00000000 + + + LO + Line Offset + 0 + 14 + + + + + NLR + NLR + number of line register + 0x44 + 0x20 + read-write + 0x00000000 + + + PL + Pixel per lines + 16 + 14 + + + NL + Number of lines + 0 + 16 + + + + + LWR + LWR + line watermark register + 0x48 + 0x20 + read-write + 0x00000000 + + + LW + Line watermark + 0 + 16 + + + + + AMTCR + AMTCR + AHB master timer configuration + register + 0x4C + 0x20 + read-write + 0x00000000 + + + DT + Dead Time + 8 + 8 + + + EN + Enable + 0 + 1 + + + + + FGCLUT + FGCLUT + FGCLUT + 0x400 + 0x20 + read-write + 0x00000000 + + + APLHA + APLHA + 24 + 8 + + + RED + RED + 16 + 8 + + + GREEN + GREEN + 8 + 8 + + + BLUE + BLUE + 0 + 8 + + + + + BGCLUT + BGCLUT + BGCLUT + 0x800 + 0x20 + read-write + 0x00000000 + + + APLHA + APLHA + 24 + 8 + + + RED + RED + 16 + 8 + + + GREEN + GREEN + 8 + 8 + + + BLUE + BLUE + 0 + 8 + + + + + + + QUADSPI + QuadSPI interface + QUADSPI + 0xA0001000 + + 0x0 + 0x1000 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PRESCALER + Clock prescaler + 24 + 8 + + + PMM + Polling match mode + 23 + 1 + + + APMS + Automatic poll mode stop + 22 + 1 + + + TOIE + TimeOut interrupt enable + 20 + 1 + + + SMIE + Status match interrupt + enable + 19 + 1 + + + FTIE + FIFO threshold interrupt + enable + 18 + 1 + + + TCIE + Transfer complete interrupt + enable + 17 + 1 + + + TEIE + Transfer error interrupt + enable + 16 + 1 + + + FTHRES + IFO threshold level + 8 + 5 + + + FSEL + FLASH memory selection + 7 + 1 + + + DFM + Dual-flash mode + 6 + 1 + + + SSHIFT + Sample shift + 4 + 1 + + + TCEN + Timeout counter enable + 3 + 1 + + + DMAEN + DMA enable + 2 + 1 + + + ABORT + Abort request + 1 + 1 + + + EN + Enable + 0 + 1 + + + + + DCR + DCR + device configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + FSIZE + FLASH memory size + 16 + 5 + + + CSHT + Chip select high time + 8 + 3 + + + CKMODE + Mode 0 / mode 3 + 0 + 1 + + + + + SR + SR + status register + 0x8 + 0x20 + read-only + 0x00000000 + + + FLEVEL + FIFO level + 8 + 7 + + + BUSY + Busy + 5 + 1 + + + TOF + Timeout flag + 4 + 1 + + + SMF + Status match flag + 3 + 1 + + + FTF + FIFO threshold flag + 2 + 1 + + + TCF + Transfer complete flag + 1 + 1 + + + TEF + Transfer error flag + 0 + 1 + + + + + FCR + FCR + flag clear register + 0xC + 0x20 + read-write + 0x00000000 + + + CTOF + Clear timeout flag + 4 + 1 + + + CSMF + Clear status match flag + 3 + 1 + + + CTCF + Clear transfer complete + flag + 1 + 1 + + + CTEF + Clear transfer error flag + 0 + 1 + + + + + DLR + DLR + data length register + 0x10 + 0x20 + read-write + 0x00000000 + + + DL + Data length + 0 + 32 + + + + + CCR + CCR + communication configuration + register + 0x14 + 0x20 + read-write + 0x00000000 + + + DDRM + Double data rate mode + 31 + 1 + + + DHHC + DDR hold half cycle + 30 + 1 + + + SIOO + Send instruction only once + mode + 28 + 1 + + + FMODE + Functional mode + 26 + 2 + + + DMODE + Data mode + 24 + 2 + + + DCYC + Number of dummy cycles + 18 + 5 + + + ABSIZE + Alternate bytes size + 16 + 2 + + + ABMODE + Alternate bytes mode + 14 + 2 + + + ADSIZE + Address size + 12 + 2 + + + ADMODE + Address mode + 10 + 2 + + + IMODE + Instruction mode + 8 + 2 + + + INSTRUCTION + Instruction + 0 + 8 + + + + + AR + AR + address register + 0x18 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Address + 0 + 32 + + + + + ABR + ABR + ABR + 0x1C + 0x20 + read-write + 0x00000000 + + + ALTERNATE + ALTERNATE + 0 + 32 + + + + + DR + DR + data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data + 0 + 32 + + + + + PSMKR + PSMKR + polling status mask register + 0x24 + 0x20 + read-write + 0x00000000 + + + MASK + Status mask + 0 + 32 + + + + + PSMAR + PSMAR + polling status match register + 0x28 + 0x20 + read-write + 0x00000000 + + + MATCH + Status match + 0 + 32 + + + + + PIR + PIR + polling interval register + 0x2C + 0x20 + read-write + 0x00000000 + + + INTERVAL + Polling interval + 0 + 16 + + + + + LPTR + LPTR + low-power timeout register + 0x30 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Timeout period + 0 + 16 + + + + + + + CEC + HDMI-CEC controller + CEC + 0x40006C00 + + 0x0 + 0x400 + registers + + + + CR + CR + control register + 0x0 + 0x20 + read-write + 0x00000000 + + + TXEOM + Tx End Of Message + 2 + 1 + + + TXSOM + Tx start of message + 1 + 1 + + + CECEN + CEC Enable + 0 + 1 + + + + + CFGR + CFGR + configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + SFT + Signal Free Time + 0 + 3 + + + RXTOL + Rx-Tolerance + 3 + 1 + + + BRESTP + Rx-stop on bit rising + error + 4 + 1 + + + BREGEN + Generate error-bit on bit rising + error + 5 + 1 + + + LBPEGEN + Generate Error-Bit on Long Bit Period + Error + 6 + 1 + + + BRDNOGEN + Avoid Error-Bit Generation in + Broadcast + 7 + 1 + + + SFTOP + SFT Option Bit + 8 + 1 + + + OAR + Own addresses + configuration + 16 + 15 + + + LSTN + Listen mode + 31 + 1 + + + + + TXDR + TXDR + Tx data register + 0x8 + 0x20 + write-only + 0x00000000 + + + TXD + Tx Data register + 0 + 8 + + + + + RXDR + RXDR + Rx Data Register + 0xC + 0x20 + read-only + 0x00000000 + + + RXDR + CEC Rx Data Register + 0 + 8 + + + + + ISR + ISR + Interrupt and Status Register + 0x10 + 0x20 + read-write + 0x00000000 + + + TXACKE + Tx-Missing acknowledge + error + 12 + 1 + + + TXERR + Tx-Error + 11 + 1 + + + TXUDR + Tx-Buffer Underrun + 10 + 1 + + + TXEND + End of Transmission + 9 + 1 + + + TXBR + Tx-Byte Request + 8 + 1 + + + ARBLST + Arbitration Lost + 7 + 1 + + + RXACKE + Rx-Missing Acknowledge + 6 + 1 + + + LBPE + Rx-Long Bit Period Error + 5 + 1 + + + SBPE + Rx-Short Bit period error + 4 + 1 + + + BRE + Rx-Bit rising error + 3 + 1 + + + RXOVR + Rx-Overrun + 2 + 1 + + + RXEND + End Of Reception + 1 + 1 + + + RXBR + Rx-Byte Received + 0 + 1 + + + + + IER + IER + interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + TXACKIE + Tx-Missing Acknowledge Error Interrupt + Enable + 12 + 1 + + + TXERRIE + Tx-Error Interrupt Enable + 11 + 1 + + + TXUDRIE + Tx-Underrun interrupt + enable + 10 + 1 + + + TXENDIE + Tx-End of message interrupt + enable + 9 + 1 + + + TXBRIE + Tx-Byte Request Interrupt + Enable + 8 + 1 + + + ARBLSTIE + Arbitration Lost Interrupt + Enable + 7 + 1 + + + RXACKIE + Rx-Missing Acknowledge Error Interrupt + Enable + 6 + 1 + + + LBPEIE + Long Bit Period Error Interrupt + Enable + 5 + 1 + + + SBPEIE + Short Bit Period Error Interrupt + Enable + 4 + 1 + + + BREIE + Bit Rising Error Interrupt + Enable + 3 + 1 + + + RXOVRIE + Rx-Buffer Overrun Interrupt + Enable + 2 + 1 + + + RXENDIE + End Of Reception Interrupt + Enable + 1 + 1 + + + RXBRIE + Rx-Byte Received Interrupt + Enable + 0 + 1 + + + + + + + SPDIF_RX + Receiver Interface + SPDIF_RX + 0x40004000 + + 0x0 + 0x400 + registers + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x00000000 + + + SPDIFEN + Peripheral Block Enable + 0 + 2 + + + RXDMAEN + Receiver DMA ENable for data + flow + 2 + 1 + + + RXSTEO + STerEO Mode + 3 + 1 + + + DRFMT + RX Data format + 4 + 2 + + + PMSK + Mask Parity error bit + 6 + 1 + + + VMSK + Mask of Validity bit + 7 + 1 + + + CUMSK + Mask of channel status and user + bits + 8 + 1 + + + PTMSK + Mask of Preamble Type bits + 9 + 1 + + + CBDMAEN + Control Buffer DMA ENable for control + flow + 10 + 1 + + + CHSEL + Channel Selection + 11 + 1 + + + NBTR + Maximum allowed re-tries during + synchronization phase + 12 + 2 + + + WFA + Wait For Activity + 14 + 1 + + + INSEL + input selection + 16 + 3 + + + + + IMR + IMR + Interrupt mask register + 0x4 + 0x20 + read-write + 0x00000000 + + + RXNEIE + RXNE interrupt enable + 0 + 1 + + + CSRNEIE + Control Buffer Ready Interrupt + Enable + 1 + 1 + + + PERRIE + Parity error interrupt + enable + 2 + 1 + + + OVRIE + Overrun error Interrupt + Enable + 3 + 1 + + + SBLKIE + Synchronization Block Detected Interrupt + Enable + 4 + 1 + + + SYNCDIE + Synchronization Done + 5 + 1 + + + IFEIE + Serial Interface Error Interrupt + Enable + 6 + 1 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-only + 0x00000000 + + + RXNE + Read data register not + empty + 0 + 1 + + + CSRNE + Control Buffer register is not + empty + 1 + 1 + + + PERR + Parity error + 2 + 1 + + + OVR + Overrun error + 3 + 1 + + + SBD + Synchronization Block + Detected + 4 + 1 + + + SYNCD + Synchronization Done + 5 + 1 + + + FERR + Framing error + 6 + 1 + + + SERR + Synchronization error + 7 + 1 + + + TERR + Time-out error + 8 + 1 + + + WIDTH5 + Duration of 5 symbols counted with + SPDIF_CLK + 16 + 15 + + + + + IFCR + IFCR + Interrupt Flag Clear register + 0xC + 0x20 + write-only + 0x00000000 + + + PERRCF + Clears the Parity error + flag + 2 + 1 + + + OVRCF + Clears the Overrun error + flag + 3 + 1 + + + SBDCF + Clears the Synchronization Block + Detected flag + 4 + 1 + + + SYNCDCF + Clears the Synchronization Done + flag + 5 + 1 + + + + + DR + DR + Data input register + 0x10 + 0x20 + read-only + 0x00000000 + + + DR + Parity Error bit + 0 + 24 + + + PE + Parity Error bit + 24 + 1 + + + V + Validity bit + 25 + 1 + + + U + User bit + 26 + 1 + + + C + Channel Status bit + 27 + 1 + + + PT + Preamble Type + 28 + 2 + + + + + CSR + CSR + Channel Status register + 0x14 + 0x20 + read-only + 0x00000000 + + + USR + User data information + 0 + 16 + + + CS + Channel A status + information + 16 + 8 + + + SOB + Start Of Block + 24 + 1 + + + + + DIR + DIR + Debug Information register + 0x18 + 0x20 + read-only + 0x00000000 + + + THI + Threshold HIGH + 0 + 13 + + + TLO + Threshold LOW + 16 + 13 + + + + + + + SDMMC1 + Secure digital input/output + interface + SDMMC + 0x40012C00 + + 0x0 + 0x400 + registers + + + SDMMC1 + SDMMC1 global interrupt + 49 + + + + POWER + POWER + power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + PWRCTRL + 0 + 2 + + + + + CLKCR + CLKCR + SDI clock control register + 0x4 + 0x20 + read-write + 0x00000000 + + + HWFC_EN + HW Flow Control enable + 14 + 1 + + + NEGEDGE + SDIO_CK dephasing selection + bit + 13 + 1 + + + WIDBUS + Wide bus mode enable bit + 11 + 2 + + + BYPASS + Clock divider bypass enable + bit + 10 + 1 + + + PWRSAV + Power saving configuration + bit + 9 + 1 + + + CLKEN + Clock enable bit + 8 + 1 + + + CLKDIV + Clock divide factor + 0 + 8 + + + + + ARG + ARG + argument register + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument + 0 + 32 + + + + + CMD + CMD + command register + 0xC + 0x20 + read-write + 0x00000000 + + + CE_ATACMD + CE-ATA command + 14 + 1 + + + nIEN + not Interrupt Enable + 13 + 1 + + + ENCMDcompl + Enable CMD completion + 12 + 1 + + + SDIOSuspend + SD I/O suspend command + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit + 10 + 1 + + + WAITPEND + CPSM Waits for ends of data transfer + (CmdPend internal signal) + 9 + 1 + + + WAITINT + CPSM waits for interrupt + request + 8 + 1 + + + WAITRESP + Wait for response bits + 6 + 2 + + + CMDINDEX + Command index + 0 + 6 + + + + + RESPCMD + RESPCMD + command response register + 0x10 + 0x20 + read-only + 0x00000000 + + + RESPCMD + Response command index + 0 + 6 + + + + + RESP1 + RESP1 + response 1..4 register + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 132 + 0 + 32 + + + + + RESP2 + RESP2 + response 1..4 register + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table 132 + 0 + 32 + + + + + RESP3 + RESP3 + response 1..4 register + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table 132 + 0 + 32 + + + + + RESP4 + RESP4 + response 1..4 register + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table 132 + 0 + 32 + + + + + DTIMER + DTIMER + data timer register + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data timeout period + 0 + 32 + + + + + DLEN + DLEN + data length register + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value + 0 + 25 + + + + + DCTRL + DCTRL + data control register + 0x2C + 0x20 + read-write + 0x00000000 + + + SDIOEN + SD I/O enable functions + 11 + 1 + + + RWMOD + Read wait mode + 10 + 1 + + + RWSTOP + Read wait stop + 9 + 1 + + + RWSTART + Read wait start + 8 + 1 + + + DBLOCKSIZE + Data block size + 4 + 4 + + + DMAEN + DMA enable bit + 3 + 1 + + + DTMODE + Data transfer mode selection 1: Stream + or SDIO multibyte data transfer + 2 + 1 + + + DTDIR + Data transfer direction + selection + 1 + 1 + + + DTEN + DTEN + 0 + 1 + + + + + DCOUNT + DCOUNT + data counter register + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value + 0 + 25 + + + + + STA + STA + status register + 0x34 + 0x20 + read-only + 0x00000000 + + + CEATAEND + CE-ATA command completion signal + received for CMD61 + 23 + 1 + + + SDIOIT + SDIO interrupt received + 22 + 1 + + + RXDAVL + Data available in receive + FIFO + 21 + 1 + + + TXDAVL + Data available in transmit + FIFO + 20 + 1 + + + RXFIFOE + Receive FIFO empty + 19 + 1 + + + TXFIFOE + Transmit FIFO empty + 18 + 1 + + + RXFIFOF + Receive FIFO full + 17 + 1 + + + TXFIFOF + Transmit FIFO full + 16 + 1 + + + RXFIFOHF + Receive FIFO half full: there are at + least 8 words in the FIFO + 15 + 1 + + + TXFIFOHE + Transmit FIFO half empty: at least 8 + words can be written into the FIFO + 14 + 1 + + + RXACT + Data receive in progress + 13 + 1 + + + TXACT + Data transmit in progress + 12 + 1 + + + CMDACT + Command transfer in + progress + 11 + 1 + + + DBCKEND + Data block sent/received (CRC check + passed) + 10 + 1 + + + STBITERR + Start bit not detected on all data + signals in wide bus mode + 9 + 1 + + + DATAEND + Data end (data counter, SDIDCOUNT, is + zero) + 8 + 1 + + + CMDSENT + Command sent (no response + required) + 7 + 1 + + + CMDREND + Command response received (CRC check + passed) + 6 + 1 + + + RXOVERR + Received FIFO overrun + error + 5 + 1 + + + TXUNDERR + Transmit FIFO underrun + error + 4 + 1 + + + DTIMEOUT + Data timeout + 3 + 1 + + + CTIMEOUT + Command response timeout + 2 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed) + 1 + 1 + + + CCRCFAIL + Command response received (CRC check + failed) + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEATAENDC + CEATAEND flag clear bit + 23 + 1 + + + SDIOITC + SDIOIT flag clear bit + 22 + 1 + + + DBCKENDC + DBCKEND flag clear bit + 10 + 1 + + + STBITERRC + STBITERR flag clear bit + 9 + 1 + + + DATAENDC + DATAEND flag clear bit + 8 + 1 + + + CMDSENTC + CMDSENT flag clear bit + 7 + 1 + + + CMDRENDC + CMDREND flag clear bit + 6 + 1 + + + RXOVERRC + RXOVERR flag clear bit + 5 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit + 4 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit + 3 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit + 2 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit + 1 + 1 + + + CCRCFAILC + CCRCFAIL flag clear bit + 0 + 1 + + + + + MASK + MASK + mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + CEATAENDIE + CE-ATA command completion signal + received interrupt enable + 23 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable + 22 + 1 + + + RXDAVLIE + Data available in Rx FIFO interrupt + enable + 21 + 1 + + + TXDAVLIE + Data available in Tx FIFO interrupt + enable + 20 + 1 + + + RXFIFOEIE + Rx FIFO empty interrupt + enable + 19 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt + enable + 18 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt + enable + 17 + 1 + + + TXFIFOFIE + Tx FIFO full interrupt + enable + 16 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt + enable + 15 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt + enable + 14 + 1 + + + RXACTIE + Data receive acting interrupt + enable + 13 + 1 + + + TXACTIE + Data transmit acting interrupt + enable + 12 + 1 + + + CMDACTIE + Command acting interrupt + enable + 11 + 1 + + + DBCKENDIE + Data block end interrupt + enable + 10 + 1 + + + STBITERRIE + Start bit error interrupt + enable + 9 + 1 + + + DATAENDIE + Data end interrupt enable + 8 + 1 + + + CMDSENTIE + Command sent interrupt + enable + 7 + 1 + + + CMDRENDIE + Command response received interrupt + enable + 6 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt + enable + 5 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt + enable + 4 + 1 + + + DTIMEOUTIE + Data timeout interrupt + enable + 3 + 1 + + + CTIMEOUTIE + Command timeout interrupt + enable + 2 + 1 + + + DCRCFAILIE + Data CRC fail interrupt + enable + 1 + 1 + + + CCRCFAILIE + Command CRC fail interrupt + enable + 0 + 1 + + + + + FIFOCNT + FIFOCNT + FIFO counter register + 0x48 + 0x20 + read-only + 0x00000000 + + + FIFOCOUNT + Remaining number of words to be written + to or read from the FIFO + 0 + 24 + + + + + FIFO + FIFO + data FIFO register + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFOData + Receive and transmit FIFO + data + 0 + 32 + + + + + + + LPTIM1 + Low power timer + LPTIM + 0x40002400 + + 0x0 + 0x400 + registers + + + + ISR + ISR + Interrupt and Status Register + 0x0 + 0x20 + read-only + 0x00000000 + + + DOWN + Counter direction change up to + down + 6 + 1 + + + UP + Counter direction change down to + up + 5 + 1 + + + ARROK + Autoreload register update + OK + 4 + 1 + + + CMPOK + Compare register update OK + 3 + 1 + + + EXTTRIG + External trigger edge + event + 2 + 1 + + + ARRM + Autoreload match + 1 + 1 + + + CMPM + Compare match + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x4 + 0x20 + write-only + 0x00000000 + + + DOWNCF + Direction change to down Clear + Flag + 6 + 1 + + + UPCF + Direction change to UP Clear + Flag + 5 + 1 + + + ARROKCF + Autoreload register update OK Clear + Flag + 4 + 1 + + + CMPOKCF + Compare register update OK Clear + Flag + 3 + 1 + + + EXTTRIGCF + External trigger valid edge Clear + Flag + 2 + 1 + + + ARRMCF + Autoreload match Clear + Flag + 1 + 1 + + + CMPMCF + compare match Clear Flag + 0 + 1 + + + + + IER + IER + Interrupt Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + DOWNIE + Direction change to down Interrupt + Enable + 6 + 1 + + + UPIE + Direction change to UP Interrupt + Enable + 5 + 1 + + + ARROKIE + Autoreload register update OK Interrupt + Enable + 4 + 1 + + + CMPOKIE + Compare register update OK Interrupt + Enable + 3 + 1 + + + EXTTRIGIE + External trigger valid edge Interrupt + Enable + 2 + 1 + + + ARRMIE + Autoreload match Interrupt + Enable + 1 + 1 + + + CMPMIE + Compare match Interrupt + Enable + 0 + 1 + + + + + CFGR + CFGR + Configuration Register + 0xC + 0x20 + read-write + 0x00000000 + + + ENC + Encoder mode enable + 24 + 1 + + + COUNTMODE + counter mode enabled + 23 + 1 + + + PRELOAD + Registers update mode + 22 + 1 + + + WAVPOL + Waveform shape polarity + 21 + 1 + + + WAVE + Waveform shape + 20 + 1 + + + TIMOUT + Timeout enable + 19 + 1 + + + TRIGEN + Trigger enable and + polarity + 17 + 2 + + + TRIGSEL + Trigger selector + 13 + 3 + + + PRESC + Clock prescaler + 9 + 3 + + + TRGFLT + Configurable digital filter for + trigger + 6 + 2 + + + CKFLT + Configurable digital filter for external + clock + 3 + 2 + + + CKPOL + Clock Polarity + 1 + 2 + + + CKSEL + Clock selector + 0 + 1 + + + + + CR + CR + Control Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTSTRT + Timer start in continuous + mode + 2 + 1 + + + SNGSTRT + LPTIM start in single mode + 1 + 1 + + + ENABLE + LPTIM Enable + 0 + 1 + + + + + CMP + CMP + Compare Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CMP + Compare value + 0 + 16 + + + + + ARR + ARR + Autoreload Register + 0x18 + 0x20 + read-write + 0x00000001 + + + ARR + Auto reload value + 0 + 16 + + + + + CNT + CNT + Counter Register + 0x1C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 16 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + PE + Peripheral enable + 0 + 1 + + + TXIE + TX Interrupt enable + 1 + 1 + + + RXIE + RX Interrupt enable + 2 + 1 + + + ADDRIE + Address match interrupt enable (slave + only) + 3 + 1 + + + NACKIE + Not acknowledge received interrupt + enable + 4 + 1 + + + STOPIE + STOP detection Interrupt + enable + 5 + 1 + + + TCIE + Transfer Complete interrupt + enable + 6 + 1 + + + ERRIE + Error interrupts enable + 7 + 1 + + + DNF + Digital noise filter + 8 + 4 + + + ANFOFF + Analog noise filter OFF + 12 + 1 + + + TXDMAEN + DMA transmission requests + enable + 14 + 1 + + + RXDMAEN + DMA reception requests + enable + 15 + 1 + + + SBC + Slave byte control + 16 + 1 + + + NOSTRETCH + Clock stretching disable + 17 + 1 + + + WUPEN + Wakeup from STOP enable + 18 + 1 + + + GCEN + General call enable + 19 + 1 + + + SMBHEN + SMBus Host address enable + 20 + 1 + + + SMBDEN + SMBus Device Default address + enable + 21 + 1 + + + ALERTEN + SMBUS alert enable + 22 + 1 + + + PECEN + PEC enable + 23 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECBYTE + Packet error checking byte + 26 + 1 + + + AUTOEND + Automatic end mode (master + mode) + 25 + 1 + + + RELOAD + NBYTES reload mode + 24 + 1 + + + NBYTES + Number of bytes + 16 + 8 + + + NACK + NACK generation (slave + mode) + 15 + 1 + + + STOP + Stop generation (master + mode) + 14 + 1 + + + START + Start generation + 13 + 1 + + + HEAD10R + 10-bit address header only read + direction (master receiver mode) + 12 + 1 + + + ADD10 + 10-bit addressing mode (master + mode) + 11 + 1 + + + RD_WRN + Transfer direction (master + mode) + 10 + 1 + + + SADD + Slave address bit (master + mode) + 0 + 10 + + + + + OAR1 + OAR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + OA1 + Interface address + 0 + 10 + + + OA1MODE + Own Address 1 10-bit mode + 10 + 1 + + + OA1EN + Own Address 1 enable + 15 + 1 + + + + + OAR2 + OAR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + OA2 + Interface address + 1 + 7 + + + OA2MSK + Own Address 2 masks + 8 + 3 + + + OA2EN + Own Address 2 enable + 15 + 1 + + + + + TIMINGR + TIMINGR + Timing register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low period (master + mode) + 0 + 8 + + + SCLH + SCL high period (master + mode) + 8 + 8 + + + SDADEL + Data hold time + 16 + 4 + + + SCLDEL + Data setup time + 20 + 4 + + + PRESC + Timing prescaler + 28 + 4 + + + + + TIMEOUTR + TIMEOUTR + Status register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + TIMEOUTA + Bus timeout A + 0 + 12 + + + TIDLE + Idle clock timeout + detection + 12 + 1 + + + TIMOUTEN + Clock timeout enable + 15 + 1 + + + TIMEOUTB + Bus timeout B + 16 + 12 + + + TEXTEN + Extended clock timeout + enable + 31 + 1 + + + + + ISR + ISR + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDCODE + Address match code (Slave + mode) + 17 + 7 + read-only + + + DIR + Transfer direction (Slave + mode) + 16 + 1 + read-only + + + BUSY + Bus busy + 15 + 1 + read-only + + + ALERT + SMBus alert + 13 + 1 + read-only + + + TIMEOUT + Timeout or t_low detection + flag + 12 + 1 + read-only + + + PECERR + PEC Error in reception + 11 + 1 + read-only + + + OVR + Overrun/Underrun (slave + mode) + 10 + 1 + read-only + + + ARLO + Arbitration lost + 9 + 1 + read-only + + + BERR + Bus error + 8 + 1 + read-only + + + TCR + Transfer Complete Reload + 7 + 1 + read-only + + + TC + Transfer Complete (master + mode) + 6 + 1 + read-only + + + STOPF + Stop detection flag + 5 + 1 + read-only + + + NACKF + Not acknowledge received + flag + 4 + 1 + read-only + + + ADDR + Address matched (slave + mode) + 3 + 1 + read-only + + + RXNE + Receive data register not empty + (receivers) + 2 + 1 + read-only + + + TXIS + Transmit interrupt status + (transmitters) + 1 + 1 + read-write + + + TXE + Transmit data register empty + (transmitters) + 0 + 1 + read-write + + + + + ICR + ICR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTCF + Alert flag clear + 13 + 1 + + + TIMOUTCF + Timeout detection flag + clear + 12 + 1 + + + PECCF + PEC Error flag clear + 11 + 1 + + + OVRCF + Overrun/Underrun flag + clear + 10 + 1 + + + ARLOCF + Arbitration lost flag + clear + 9 + 1 + + + BERRCF + Bus error flag clear + 8 + 1 + + + STOPCF + Stop detection flag clear + 5 + 1 + + + NACKCF + Not Acknowledge flag clear + 4 + 1 + + + ADDRCF + Address Matched flag clear + 3 + 1 + + + + + PECR + PECR + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PEC + Packet error checking + register + 0 + 8 + + + + + RXDR + RXDR + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + RXDATA + 8-bit receive data + 0 + 8 + + + + + TXDR + TXDR + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + TXDATA + 8-bit transmit data + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + + I2C3 + 0x40005C00 + + + I2C4 + 0x40006000 + + + RTC + Real-time clock + RTC + 0x40002800 + + 0x0 + 0x400 + registers + + + RTC_WKUP + RTC Tamper or TimeStamp /CSS on LSE through + EXTI line 19 interrupts + 3 + + + RTC_ALARM + RTC alarms through EXTI line 18 + interrupts + 41 + + + + TR + TR + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + DR + DR + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens in BCD format + 20 + 4 + + + YU + Year units in BCD format + 16 + 4 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + CR + CR + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + WCKSEL + Wakeup clock selection + 0 + 3 + + + TSEDGE + Time-stamp event active + edge + 3 + 1 + + + REFCKON + Reference clock detection enable (50 or + 60 Hz) + 4 + 1 + + + BYPSHAD + Bypass the shadow + registers + 5 + 1 + + + FMT + Hour format + 6 + 1 + + + ALRAE + Alarm A enable + 8 + 1 + + + ALRBE + Alarm B enable + 9 + 1 + + + WUTE + Wakeup timer enable + 10 + 1 + + + TSE + Time stamp enable + 11 + 1 + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + + + ADD1H + Add 1 hour (summer time + change) + 16 + 1 + + + SUB1H + Subtract 1 hour (winter time + change) + 17 + 1 + + + BKP + Backup + 18 + 1 + + + COSEL + Calibration output + selection + 19 + 1 + + + POL + Output polarity + 20 + 1 + + + OSEL + Output selection + 21 + 2 + + + COE + Calibration output enable + 23 + 1 + + + ITSE + timestamp on internal event + enable + 24 + 1 + + + + + ISR + ISR + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag + 2 + 1 + read-only + + + SHPF + Shift operation pending + 3 + 1 + read-write + + + INITS + Initialization status flag + 4 + 1 + read-only + + + RSF + Registers synchronization + flag + 5 + 1 + read-write + + + INITF + Initialization flag + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag + 8 + 1 + read-write + + + ALRBF + Alarm B flag + 9 + 1 + read-write + + + WUTF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Time-stamp flag + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag + 12 + 1 + read-write + + + TAMP1F + Tamper detection flag + 13 + 1 + read-write + + + TAMP2F + RTC_TAMP2 detection flag + 14 + 1 + read-write + + + TAMP3F + RTC_TAMP3 detection flag + 15 + 1 + read-write + + + RECALPF + Recalibration pending Flag + 16 + 1 + read-only + + + + + PRER + PRER + prescaler register + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_A + Asynchronous prescaler + factor + 16 + 7 + + + PREDIV_S + Synchronous prescaler + factor + 0 + 15 + + + + + WUTR + WUTR + wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value + bits + 0 + 16 + + + + + ALRMAR + ALRMAR + alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm A date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + ALRMBR + ALRMBR + alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MSK4 + Alarm B date mask + 31 + 1 + + + WDSEL + Week day selection + 30 + 1 + + + DT + Date tens in BCD format + 28 + 2 + + + DU + Date units or day in BCD + format + 24 + 4 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + PM + AM/PM notation + 22 + 1 + + + HT + Hour tens in BCD format + 20 + 2 + + + HU + Hour units in BCD format + 16 + 4 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + ST + Second tens in BCD format + 4 + 3 + + + SU + Second units in BCD format + 0 + 4 + + + + + WPR + WPR + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key + 0 + 8 + + + + + SSR + SSR + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + SHIFTR + SHIFTR + shift control register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add one second + 31 + 1 + + + SUBFS + Subtract a fraction of a + second + 0 + 15 + + + + + TSTR + TSTR + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + TSDR + TSDR + time stamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WDU + Week day units + 13 + 3 + + + MT + Month tens in BCD format + 12 + 1 + + + MU + Month units in BCD format + 8 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + DU + Date units in BCD format + 0 + 4 + + + + + TSSSR + TSSSR + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value + 0 + 16 + + + + + CALR + CALR + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + CALP + Increase frequency of RTC by 488.5 + ppm + 15 + 1 + + + CALW8 + Use an 8-second calibration cycle + period + 14 + 1 + + + CALW16 + Use a 16-second calibration cycle + period + 13 + 1 + + + CALM + Calibration minus + 0 + 9 + + + + + TAMPCR + TAMPCR + tamper configuration register + 0x40 + 0x20 + read-write + 0x00000000 + + + TAMP1E + Tamper 1 detection enable + 0 + 1 + + + TAMP1TRG + Active level for tamper 1 + 1 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP2E + Tamper 2 detection enable + 3 + 1 + + + TAMP2TRG + Active level for tamper 2 + 4 + 1 + + + TAMP3E + Tamper 3 detection enable + 5 + 1 + + + TAMP3TRG + Active level for tamper 3 + 6 + 1 + + + TAMPTS + Activate timestamp on tamper detection + event + 7 + 1 + + + TAMPFREQ + Tamper sampling frequency + 8 + 3 + + + TAMPFLT + Tamper filter count + 11 + 2 + + + TAMPPRCH + Tamper precharge duration + 13 + 2 + + + TAMPPUDIS + TAMPER pull-up disable + 15 + 1 + + + TAMP1IE + Tamper 1 interrupt enable + 16 + 1 + + + TAMP1NOERASE + Tamper 1 no erase + 17 + 1 + + + TAMP1MF + Tamper 1 mask flag + 18 + 1 + + + TAMP2IE + Tamper 2 interrupt enable + 19 + 1 + + + TAMP2NOERASE + Tamper 2 no erase + 20 + 1 + + + TAMP2MF + Tamper 2 mask flag + 21 + 1 + + + TAMP3IE + Tamper 3 interrupt enable + 22 + 1 + + + TAMP3NOERASE + Tamper 3 no erase + 23 + 1 + + + TAMP3MF + Tamper 3 mask flag + 24 + 1 + + + + + ALRMASSR + ALRMASSR + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + ALRMBSSR + ALRMBSSR + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + MASKSS + Mask the most-significant bits starting + at this bit + 24 + 4 + + + SS + Sub seconds value + 0 + 15 + + + + + OR + OR + option register + 0x4C + 0x20 + read-write + 0x00000000 + + + RTC_ALARM_TYPE + RTC_ALARM on PC13 output + type + 0 + 1 + + + RTC_OUT_RMP + RTC_OUT remap + 1 + 1 + + + + + BKP0R + BKP0R + backup register + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP1R + BKP1R + backup register + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP2R + BKP2R + backup register + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP3R + BKP3R + backup register + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP4R + BKP4R + backup register + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP5R + BKP5R + backup register + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP6R + BKP6R + backup register + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP7R + BKP7R + backup register + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP8R + BKP8R + backup register + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP9R + BKP9R + backup register + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP10R + BKP10R + backup register + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP11R + BKP11R + backup register + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP12R + BKP12R + backup register + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP13R + BKP13R + backup register + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP14R + BKP14R + backup register + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP15R + BKP15R + backup register + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP16R + BKP16R + backup register + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP17R + BKP17R + backup register + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP18R + BKP18R + backup register + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP19R + BKP19R + backup register + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP20R + BKP20R + backup register + 0xA0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP21R + BKP21R + backup register + 0xA4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP22R + BKP22R + backup register + 0xA8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP23R + BKP23R + backup register + 0xAC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP24R + BKP24R + backup register + 0xB0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP25R + BKP25R + backup register + 0xB4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP26R + BKP26R + backup register + 0xB8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP27R + BKP27R + backup register + 0xBC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP28R + BKP28R + backup register + 0xC0 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP29R + BKP29R + backup register + 0xC4 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP30R + BKP30R + backup register + 0xC8 + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + BKP31R + BKP31R + backup register + 0xCC + 0x20 + read-write + 0x00000000 + + + BKP + BKP + 0 + 32 + + + + + + + USART6 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011400 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + M1 + Word length + 28 + 1 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT4 + Driver Enable assertion + time + 25 + 1 + + + DEAT3 + DEAT3 + 24 + 1 + + + DEAT2 + DEAT2 + 23 + 1 + + + DEAT1 + DEAT1 + 22 + 1 + + + DEAT0 + DEAT0 + 21 + 1 + + + DEDT4 + Driver Enable de-assertion + time + 20 + 1 + + + DEDT3 + DEDT3 + 19 + 1 + + + DEDT2 + DEDT2 + 18 + 1 + + + DEDT1 + DEDT1 + 17 + 1 + + + DEDT0 + DEDT0 + 16 + 1 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UESM + USART enable in Stop mode + 1 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4_7 + Address of the USART node + 28 + 4 + + + ADD0_3 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD1 + Auto baud rate mode + 22 + 1 + + + ABRMOD0 + ABRMOD0 + 21 + 1 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + TAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + WUFIE + Wakeup from Stop mode interrupt + enable + 22 + 1 + + + WUS + Wakeup from Stop mode interrupt flag + selection + 20 + 2 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + Ir low-power + 2 + 1 + + + IREN + Ir mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + DIV_Mantissa + DIV_Mantissa + 4 + 12 + + + DIV_Fraction + DIV_Fraction + 0 + 4 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + REACK + REACK + 22 + 1 + + + TEACK + TEACK + 21 + 1 + + + WUF + WUF + 20 + 1 + + + RWU + RWU + 19 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + ABRF + ABRF + 15 + 1 + + + ABRE + ABRE + 14 + 1 + + + EOBF + EOBF + 12 + 1 + + + RTOF + RTOF + 11 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + LBDF + LBDF + 8 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NF + NF + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + WUCF + Wakeup from Stop mode clear + flag + 20 + 1 + + + CMCF + Character match clear flag + 17 + 1 + + + EOBCF + End of block clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + + + USART1 + 0x40011000 + + USART1 + USART1 global interrupt + 37 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + UART4 + 0x40004C00 + + + UART8 + 0x40007C00 + + UART8 + UART 8 global interrupt + 83 + + + + UART7 + 0x40007800 + + + OTG_FS_GLOBAL + USB on the go full speed + USB_OTG_FS + 0x50000000 + + 0x0 + 0x400 + registers + + + + OTG_FS_GOTGCTL + OTG_FS_GOTGCTL + OTG_FS control and status register + (OTG_FS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + VBVALOEN + VBUS valid override enable + 2 + 1 + read-write + + + VBVALOVAL + VBUS valid override value + 3 + 1 + read-write + + + AVALOEN + A-peripheral session valid override + enable + 4 + 1 + read-write + + + AVALOVAL + A-peripheral session valid override + value + 5 + 1 + read-write + + + BVALOEN + B-peripheral session valid override + enable + 6 + 1 + read-write + + + BVALOVAL + B-peripheral session valid override + value + 7 + 1 + read-write + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + OTGVER + OTG version + 20 + 1 + read-write + + + + + OTG_FS_GOTGINT + OTG_FS_GOTGINT + OTG_FS interrupt register + (OTG_FS_GOTGINT) + 0x4 + 0x20 + read-write + 0x00000000 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_FS_GAHBCFG + OTG_FS_GAHBCFG + OTG_FS AHB configuration register + (OTG_FS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GINT + Global interrupt mask + 0 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_FS_GUSBCFG + OTG_FS_GUSBCFG + OTG_FS USB configuration register + (OTG_FS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + Full Speed serial transceiver + select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + FHMOD + Force host mode + 29 + 1 + read-write + + + FDMOD + Force device mode + 30 + 1 + read-write + + + + + OTG_FS_GRSTCTL + OTG_FS_GRSTCTL + OTG_FS reset register + (OTG_FS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + + + OTG_FS_GINTSTS + OTG_FS_GINTSTS + OTG_FS core interrupt register + (OTG_FS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFE + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + IPXFR_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + RSTDET + Reset detected interrupt + 23 + 1 + read-write + + + + + OTG_FS_GINTMSK + OTG_FS_GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEM + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + IPXFRM_IISOOXFRM + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDETM + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMIN + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_FS_GRXSTSR_Device + OTG_FS_GRXSTSR_Device + OTG_FS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSR_Host + OTG_FS_GRXSTSR_Host + OTG_FS Receive status debug read(Host + mode) + OTG_FS_GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GRXFSIZ + OTG_FS_GRXFSIZ + OTG_FS Receive FIFO size register + (OTG_FS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_FS_DIEPTXF0_Device + OTG_FS_DIEPTXF0_Device + OTG_FS Endpoint 0 Transmit FIFO + size + 0x28 + 0x20 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXFSIZ_Host + OTG_FS_HNPTXFSIZ_Host + OTG_FS Host non-periodic transmit FIFO size + register + OTG_FS_DIEPTXF0_Device + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSA + Non-periodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Non-periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_HNPTXSTS + OTG_FS_HNPTXSTS + OTG_FS non-periodic transmit FIFO/queue + status register (OTG_FS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSAV + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + OTG_FS_GCCFG + OTG_FS_GCCFG + OTG_FS general core configuration register + (OTG_FS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_FS_CID + OTG_FS_CID + core ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_FS_HPTXFSIZ + OTG_FS_HPTXFSIZ + OTG_FS Host periodic transmit FIFO size + register (OTG_FS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZ + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF1 + OTG_FS_DIEPTXF1 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF2 + OTG_FS_DIEPTXF2 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF3 + OTG_FS_DIEPTXF3 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_FS_GRXSTSP_Device + OTG_FS_GRXSTSP_Device + OTG status read and pop register (Device + mode) + 0x20 + 0x20 + read-only + 0x02000400 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_FS_GRXSTSP_Host + OTG_FS_GRXSTSP_Host + OTG status read and pop register (Host + mode) + OTG_FS_GRXSTSP_Device + 0x20 + 0x20 + read-only + 0x02000400 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_FS_GI2CCTL + OTG_FS_GI2CCTL + OTG I2C access register + 0x30 + 0x20 + read-write + 0x02000400 + + + RWDATA + I2C Read/Write Data + 0 + 8 + + + REGADDR + I2C Register Address + 8 + 8 + + + ADDR + I2C Address + 16 + 7 + + + I2CEN + I2C Enable + 23 + 1 + + + ACK + I2C ACK + 24 + 1 + + + I2CDEVADR + I2C Device Address + 26 + 2 + + + I2CDATSE0 + I2C DatSe0 USB mode + 28 + 1 + + + RW + Read/Write Indicator + 30 + 1 + + + BSYDNE + I2C Busy/Done + 31 + 1 + + + + + OTG_FS_GPWRDN + OTG_FS_GPWRDN + OTG power down register + 0x58 + 0x20 + read-write + 0x02000400 + + + ADPMEN + ADP module enable + 0 + 1 + + + ADPIF + ADP interrupt flag + 23 + 1 + + + + + OTG_FS_GADPCTL + OTG_FS_GADPCTL + OTG ADP timer, control and status + register + 0x60 + 0x20 + 0x02000400 + + + PRBDSCHG + Probe discharge + 0 + 2 + read-write + + + PRBDELTA + Probe delta + 2 + 2 + read-write + + + PRBPER + Probe period + 4 + 2 + read-write + + + RTIM + Ramp time + 6 + 11 + read-only + + + ENAPRB + Enable probe + 17 + 1 + read-write + + + ENASNS + Enable sense + 18 + 1 + read-write + + + ADPRST + ADP reset + 19 + 1 + read-only + + + ADPEN + ADP enable + 20 + 1 + read-write + + + ADPPRBIF + ADP probe interrupt flag + 21 + 1 + read-write + + + ADPSNSIF + ADP sense interrupt flag + 22 + 1 + read-write + + + ADPTOIF + ADP timeout interrupt flag + 23 + 1 + read-write + + + ADPPRBIM + ADP probe interrupt mask + 24 + 1 + read-write + + + ADPSNSIM + ADP sense interrupt mask + 25 + 1 + read-write + + + ADPTOIM + ADP timeout interrupt mask + 26 + 1 + read-write + + + AR + Access request + 27 + 2 + read-write + + + + + OTG_FS_DIEPTXF4 + OTG_FS_DIEPTXF4 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_DIEPTXF5 + OTG_FS_DIEPTXF5 + OTG_FS device IN endpoint transmit FIFO size + register (OTG_FS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint Tx FIFO depth + 16 + 16 + + + + + OTG_FS_GLPMCFG + OTG_FS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 0x20 + 0x02000400 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-write + + + REMWAKE + bRemoteWake value + 6 + 1 + read-write + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG_FS_HOST + USB on the go full speed + USB_OTG_FS + 0x50000400 + + 0x0 + 0x400 + registers + + + + OTG_FS_HCFG + OTG_FS_HCFG + OTG_FS host configuration register + (OTG_FS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_FS_HFIR + OTG_FS_HFIR + OTG_FS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_FS_HFNUM + OTG_FS_HFNUM + OTG_FS host frame number/frame time + remaining register (OTG_FS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_FS_HPTXSTS + OTG_FS_HPTXSTS + OTG_FS_Host periodic transmit FIFO/queue + status register (OTG_FS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_FS_HAINT + OTG_FS_HAINT + OTG_FS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_FS_HAINTMSK + OTG_FS_HAINTMSK + OTG_FS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_FS_HPRT + OTG_FS_HPRT + OTG_FS host port control and status register + (OTG_FS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_FS_HCCHAR0 + OTG_FS_HCCHAR0 + OTG_FS host channel-0 characteristics + register (OTG_FS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR1 + OTG_FS_HCCHAR1 + OTG_FS host channel-1 characteristics + register (OTG_FS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR2 + OTG_FS_HCCHAR2 + OTG_FS host channel-2 characteristics + register (OTG_FS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR3 + OTG_FS_HCCHAR3 + OTG_FS host channel-3 characteristics + register (OTG_FS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR4 + OTG_FS_HCCHAR4 + OTG_FS host channel-4 characteristics + register (OTG_FS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR5 + OTG_FS_HCCHAR5 + OTG_FS host channel-5 characteristics + register (OTG_FS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR6 + OTG_FS_HCCHAR6 + OTG_FS host channel-6 characteristics + register (OTG_FS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCCHAR7 + OTG_FS_HCCHAR7 + OTG_FS host channel-7 characteristics + register (OTG_FS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT0 + OTG_FS_HCINT0 + OTG_FS host channel-0 interrupt register + (OTG_FS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT1 + OTG_FS_HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT2 + OTG_FS_HCINT2 + OTG_FS host channel-2 interrupt register + (OTG_FS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT3 + OTG_FS_HCINT3 + OTG_FS host channel-3 interrupt register + (OTG_FS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT4 + OTG_FS_HCINT4 + OTG_FS host channel-4 interrupt register + (OTG_FS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT5 + OTG_FS_HCINT5 + OTG_FS host channel-5 interrupt register + (OTG_FS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT6 + OTG_FS_HCINT6 + OTG_FS host channel-6 interrupt register + (OTG_FS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINT7 + OTG_FS_HCINT7 + OTG_FS host channel-7 interrupt register + (OTG_FS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK0 + OTG_FS_HCINTMSK0 + OTG_FS host channel-0 mask register + (OTG_FS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK1 + OTG_FS_HCINTMSK1 + OTG_FS host channel-1 mask register + (OTG_FS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK2 + OTG_FS_HCINTMSK2 + OTG_FS host channel-2 mask register + (OTG_FS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK3 + OTG_FS_HCINTMSK3 + OTG_FS host channel-3 mask register + (OTG_FS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK4 + OTG_FS_HCINTMSK4 + OTG_FS host channel-4 mask register + (OTG_FS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK5 + OTG_FS_HCINTMSK5 + OTG_FS host channel-5 mask register + (OTG_FS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK6 + OTG_FS_HCINTMSK6 + OTG_FS host channel-6 mask register + (OTG_FS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCINTMSK7 + OTG_FS_HCINTMSK7 + OTG_FS host channel-7 mask register + (OTG_FS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ0 + OTG_FS_HCTSIZ0 + OTG_FS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ1 + OTG_FS_HCTSIZ1 + OTG_FS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ2 + OTG_FS_HCTSIZ2 + OTG_FS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ3 + OTG_FS_HCTSIZ3 + OTG_FS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ4 + OTG_FS_HCTSIZ4 + OTG_FS host channel-x transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ5 + OTG_FS_HCTSIZ5 + OTG_FS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ6 + OTG_FS_HCTSIZ6 + OTG_FS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCTSIZ7 + OTG_FS_HCTSIZ7 + OTG_FS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR8 + OTG_FS_HCCHAR8 + OTG_FS host channel-8 characteristics + register + 0x1F4 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT8 + OTG_FS_HCINT8 + OTG_FS host channel-8 interrupt + register + 0x1F8 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK8 + OTG_FS_HCINTMSK8 + OTG_FS host channel-8 mask + register + 0x1FC + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ8 + OTG_FS_HCTSIZ8 + OTG_FS host channel-8 transfer size + register + 0x200 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR9 + OTG_FS_HCCHAR9 + OTG_FS host channel-9 characteristics + register + 0x204 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT9 + OTG_FS_HCINT9 + OTG_FS host channel-9 interrupt + register + 0x208 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK9 + OTG_FS_HCINTMSK9 + OTG_FS host channel-9 mask + register + 0x20C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ9 + OTG_FS_HCTSIZ9 + OTG_FS host channel-9 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR10 + OTG_FS_HCCHAR10 + OTG_FS host channel-10 characteristics + register + 0x214 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT10 + OTG_FS_HCINT10 + OTG_FS host channel-10 interrupt + register + 0x218 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK10 + OTG_FS_HCINTMSK10 + OTG_FS host channel-10 mask + register + 0x21C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ10 + OTG_FS_HCTSIZ10 + OTG_FS host channel-10 transfer size + register + 0x220 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_FS_HCCHAR11 + OTG_FS_HCCHAR11 + OTG_FS host channel-11 characteristics + register + 0x224 + 0x20 + read-write + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MCNT + Multicount + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_FS_HCINT11 + OTG_FS_HCINT11 + OTG_FS host channel-11 interrupt + register + 0x228 + 0x20 + read-write + 0x00000000 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_FS_HCINTMSK11 + OTG_FS_HCINTMSK11 + OTG_FS host channel-11 mask + register + 0x22C + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_FS_HCTSIZ11 + OTG_FS_HCTSIZ11 + OTG_FS host channel-11 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + + + OTG_FS_DEVICE + USB on the go full speed + USB_OTG_FS + 0x50000800 + + 0x0 + 0x400 + registers + + + + OTG_FS_DCFG + OTG_FS_DCFG + OTG_FS device configuration register + (OTG_FS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Non-zero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic frame interval + 11 + 2 + + + + + OTG_FS_DCTL + OTG_FS_DCTL + OTG_FS device control register + (OTG_FS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + read-write + + + CGINAK + Clear global IN NAK + 8 + 1 + read-write + + + SGONAK + Set global OUT NAK + 9 + 1 + read-write + + + CGONAK + Clear global OUT NAK + 10 + 1 + read-write + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_FS_DSTS + OTG_FS_DSTS + OTG_FS device status register + (OTG_FS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_FS_DIEPMSK + OTG_FS_DIEPMSK + OTG_FS device IN endpoint common interrupt + mask register (OTG_FS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + + + OTG_FS_DOEPMSK + OTG_FS_DOEPMSK + OTG_FS device OUT endpoint common interrupt + mask register (OTG_FS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + + + OTG_FS_DAINT + OTG_FS_DAINT + OTG_FS device all endpoints interrupt + register (OTG_FS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DAINTMSK + OTG_FS_DAINTMSK + OTG_FS all endpoints interrupt mask register + (OTG_FS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_FS_DVBUSDIS + OTG_FS_DVBUSDIS + OTG_FS device VBUS discharge time + register + 0x28 + 0x20 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_FS_DVBUSPULSE + OTG_FS_DVBUSPULSE + OTG_FS device VBUS pulsing time + register + 0x2C + 0x20 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_FS_DIEPEMPMSK + OTG_FS_DIEPEMPMSK + OTG_FS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_FS_DIEPCTL0 + OTG_FS_DIEPCTL0 + OTG_FS device control IN endpoint 0 control + register (OTG_FS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + read-only + + + + + OTG_FS_DIEPCTL1 + OTG_FS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM_SD1PID + SODDFRM/SD1PID + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL2 + OTG_FS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPCTL3 + OTG_FS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL0 + OTG_FS_DOEPCTL0 + device endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + EPENA + EPENA + 31 + 1 + write-only + + + EPDIS + EPDIS + 30 + 1 + read-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-only + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-only + + + MPSIZ + MPSIZ + 0 + 2 + read-only + + + + + OTG_FS_DOEPCTL1 + OTG_FS_DOEPCTL1 + device endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL2 + OTG_FS_DOEPCTL2 + device endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPCTL3 + OTG_FS_DOEPCTL3 + device endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT0 + OTG_FS_DIEPINT0 + device endpoint-x interrupt + register + 0x108 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT1 + OTG_FS_DIEPINT1 + device endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT2 + OTG_FS_DIEPINT2 + device endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPINT3 + OTG_FS_DIEPINT3 + device endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DOEPINT0 + OTG_FS_DOEPINT0 + device endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT1 + OTG_FS_DOEPINT1 + device endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT2 + OTG_FS_DOEPINT2 + device endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPINT3 + OTG_FS_DOEPINT3 + device endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DIEPTSIZ0 + OTG_FS_DIEPTSIZ0 + device endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + PKTCNT + Packet count + 19 + 2 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DOEPTSIZ0 + OTG_FS_DOEPTSIZ0 + device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + STUPCNT + SETUP packet count + 29 + 2 + + + PKTCNT + Packet count + 19 + 1 + + + XFRSIZ + Transfer size + 0 + 7 + + + + + OTG_FS_DIEPTSIZ1 + OTG_FS_DIEPTSIZ1 + device endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ2 + OTG_FS_DIEPTSIZ2 + device endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPTSIZ3 + OTG_FS_DIEPTSIZ3 + device endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS0 + OTG_FS_DTXFSTS0 + OTG_FS device IN endpoint transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS1 + OTG_FS_DTXFSTS1 + OTG_FS device IN endpoint transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS2 + OTG_FS_DTXFSTS2 + OTG_FS device IN endpoint transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DTXFSTS3 + OTG_FS_DTXFSTS3 + OTG_FS device IN endpoint transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPTSIZ1 + OTG_FS_DOEPTSIZ1 + device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ2 + OTG_FS_DOEPTSIZ2 + device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPTSIZ3 + OTG_FS_DOEPTSIZ3 + device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DIEPCTL4 + OTG_FS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT4 + OTG_FS_DIEPINT4 + device endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ4 + OTG_FS_DIEPTSIZ4 + device endpoint-4 transfer size + register + 0x194 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS4 + OTG_FS_DTXFSTS4 + OTG_FS device IN endpoint transmit FIFO + status register + 0x19C + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DIEPCTL5 + OTG_FS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + TXFNUM + TXFNUM + 22 + 4 + read-write + + + Stall + Stall + 21 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DIEPINT5 + OTG_FS_DIEPINT5 + device endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000000 + + + TXFE + TXFE + 7 + 1 + read-only + + + INEPNE + INEPNE + 6 + 1 + read-write + + + ITTXFE + ITTXFE + 4 + 1 + read-write + + + TOC + TOC + 3 + 1 + read-write + + + EPDISD + EPDISD + 1 + 1 + read-write + + + XFRC + XFRC + 0 + 1 + read-write + + + + + OTG_FS_DIEPTSIZ55 + OTG_FS_DIEPTSIZ55 + device endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + MCNT + Multi count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DTXFSTS55 + OTG_FS_DTXFSTS55 + OTG_FS device IN endpoint transmit FIFO + status register + 0x1B8 + 0x20 + read-write + 0x00000000 + + + INEPTFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + OTG_FS_DOEPCTL4 + OTG_FS_DOEPCTL4 + device endpoint-4 control + register + 0x378 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT4 + OTG_FS_DOEPINT4 + device endpoint-4 interrupt + register + 0x380 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ4 + OTG_FS_DOEPTSIZ4 + device OUT endpoint-4 transfer size + register + 0x388 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + OTG_FS_DOEPCTL5 + OTG_FS_DOEPCTL5 + device endpoint-5 control + register + 0x390 + 0x20 + 0x00000000 + + + EPENA + EPENA + 31 + 1 + read-write + + + EPDIS + EPDIS + 30 + 1 + read-write + + + SODDFRM + SODDFRM + 29 + 1 + write-only + + + SD0PID_SEVNFRM + SD0PID/SEVNFRM + 28 + 1 + write-only + + + SNAK + SNAK + 27 + 1 + write-only + + + CNAK + CNAK + 26 + 1 + write-only + + + Stall + Stall + 21 + 1 + read-write + + + SNPM + SNPM + 20 + 1 + read-write + + + EPTYP + EPTYP + 18 + 2 + read-write + + + NAKSTS + NAKSTS + 17 + 1 + read-only + + + EONUM_DPID + EONUM/DPID + 16 + 1 + read-only + + + USBAEP + USBAEP + 15 + 1 + read-write + + + MPSIZ + MPSIZ + 0 + 11 + read-write + + + + + OTG_FS_DOEPINT5 + OTG_FS_DOEPINT5 + device endpoint-5 interrupt + register + 0x398 + 0x20 + read-write + 0x00000000 + + + B2BSTUP + B2BSTUP + 6 + 1 + + + OTEPDIS + OTEPDIS + 4 + 1 + + + STUP + STUP + 3 + 1 + + + EPDISD + EPDISD + 1 + 1 + + + XFRC + XFRC + 0 + 1 + + + + + OTG_FS_DOEPTSIZ5 + OTG_FS_DOEPTSIZ5 + device OUT endpoint-5 transfer size + register + 0x3A0 + 0x20 + read-write + 0x00000000 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + PKTCNT + Packet count + 19 + 10 + + + XFRSIZ + Transfer size + 0 + 19 + + + + + + + OTG_FS_PWRCLK + USB on the go full speed + USB_OTG_FS + 0x50000E00 + + 0x0 + 0x400 + registers + + + OTG_FS_WKUP + USB On-The-Go FS Wakeup through EXTI line + interrupt + 42 + + + OTG_FS + USB On The Go FS global + interrupt + 67 + + + + OTG_FS_PCGCCTL + OTG_FS_PCGCCTL + OTG_FS power and clock gating control + register (OTG_FS_PCGCCTL) + 0x0 + 0x20 + read-write + 0x00000000 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY Suspended + 4 + 1 + + + + + + + OTG_HS_GLOBAL + USB on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + DMAREQ + DMA request signal enabled for USB OTG + HS + 30 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDE + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMINTM + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_HNPTXFSIZ_Host + OTG_HS_HNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF0_Device + OTG_HS_DIEPTXF0_Device + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_HNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Device + OTG_HS_GRXSTSR_Device + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Device + OTG_HS_GRXSTSP_Device + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GLPMCFG + OTG_HS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 32 + 0x0 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-only + + + REMWAKE + bRemoteWake value + 6 + 1 + read-only + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG_HS_HOST + USB on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR12 + OTG_HS_HCCHAR12 + OTG_HS host channel-12 characteristics + register + 0x278 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT12 + OTG_HS_HCSPLT12 + OTG_HS host channel-12 split control + register + 0x27C + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT12 + OTG_HS_HCINT12 + OTG_HS host channel-12 interrupt + register + 0x280 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK12 + OTG_HS_HCINTMSK12 + OTG_HS host channel-12 interrupt mask + register + 0x284 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ12 + OTG_HS_HCTSIZ12 + OTG_HS host channel-12 transfer size + register + 0x288 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA12 + OTG_HS_HCDMA12 + OTG_HS host channel-12 DMA address + register + 0x28C + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR13 + OTG_HS_HCCHAR13 + OTG_HS host channel-13 characteristics + register + 0x290 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT13 + OTG_HS_HCSPLT13 + OTG_HS host channel-13 split control + register + 0x294 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT13 + OTG_HS_HCINT13 + OTG_HS host channel-13 interrupt + register + 0x298 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK13 + OTG_HS_HCINTMSK13 + OTG_HS host channel-13 interrupt mask + register + 0x29C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALLM response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ13 + OTG_HS_HCTSIZ13 + OTG_HS host channel-13 transfer size + register + 0x2A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA13 + OTG_HS_HCDMA13 + OTG_HS host channel-13 DMA address + register + 0x2A4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR14 + OTG_HS_HCCHAR14 + OTG_HS host channel-14 characteristics + register + 0x2A8 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT14 + OTG_HS_HCSPLT14 + OTG_HS host channel-14 split control + register + 0x2AC + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT14 + OTG_HS_HCINT14 + OTG_HS host channel-14 interrupt + register + 0x2B0 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK14 + OTG_HS_HCINTMSK14 + OTG_HS host channel-14 interrupt mask + register + 0x2B4 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAKM response received interrupt + mask + 4 + 1 + + + ACKM + ACKM response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ14 + OTG_HS_HCTSIZ14 + OTG_HS host channel-14 transfer size + register + 0x2B8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA14 + OTG_HS_HCDMA14 + OTG_HS host channel-14 DMA address + register + 0x2BC + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR15 + OTG_HS_HCCHAR15 + OTG_HS host channel-15 characteristics + register + 0x2C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT15 + OTG_HS_HCSPLT15 + OTG_HS host channel-15 split control + register + 0x2C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT15 + OTG_HS_HCINT15 + OTG_HS host channel-15 interrupt + register + 0x2C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK15 + OTG_HS_HCINTMSK15 + OTG_HS host channel-15 interrupt mask + register + 0x2CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ15 + OTG_HS_HCTSIZ15 + OTG_HS host channel-15 transfer size + register + 0x2D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA15 + OTG_HS_HCDMA15 + OTG_HS host channel-15 DMA address + register + 0x2D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG_HS_DEVICE + USB on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-0 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-1 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-2 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-3 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-4 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ6 + OTG_HS_DIEPTSIZ6 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPCTL5 + 0x1A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS6 + OTG_HS_DTXFSTS6 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1A4 + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ7 + OTG_HS_DIEPTSIZ7 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPINT5 + 0x1A8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS7 + OTG_HS_DTXFSTS7 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1AC + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DOEPCTL4 + OTG_HS_DOEPCTL4 + OTG device endpoint-4 control + register + 0x380 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL5 + OTG_HS_DOEPCTL5 + OTG device endpoint-5 control + register + 0x3A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL6 + OTG_HS_DOEPCTL6 + OTG device endpoint-6 control + register + 0x3C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL7 + OTG_HS_DOEPCTL7 + OTG device endpoint-7 control + register + 0x3E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPTSIZ5 + OTG_HS_DOEPTSIZ5 + OTG_HS device endpoint-5 transfer size + register + 0x3B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ6 + OTG_HS_DOEPTSIZ6 + OTG_HS device endpoint-6 transfer size + register + 0x3D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ7 + OTG_HS_DOEPTSIZ7 + OTG_HS device endpoint-7 transfer size + register + 0x3F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG_HS_PWRCLK + USB on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + OTG_HS_EP1_OUT + USB On The Go HS End Point 1 Out global + interrupt + 74 + + + OTG_HS_EP1_IN + USB On The Go HS End Point 1 In global + interrupt + 75 + + + OTG_HS_WKUP + USB On The Go HS Wakeup through EXTI + interrupt + 76 + + + OTG_HS + USB On The Go HS global + interrupt + 77 + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x355 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-only + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CSR + CSR + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + RVR + RVR + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + CVR + CVR + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISFOLD + DISFOLD + 2 + 1 + + + FPEXCODIS + FPEXCODIS + 10 + 1 + + + DISRAMODE + DISRAMODE + 11 + 1 + + + DISITMATBFLUSH + DISITMATBFLUSH + 12 + 1 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + DC + DC + 16 + 1 + + + IC + IC + 17 + 1 + + + BP + BP + 18 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCRS + SHCRS + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + IACCVIOL + 0 + 1 + + + DACCVIOL + DACCVIOL + 1 + 1 + + + MUNSTKERR + MUNSTKERR + 3 + 1 + + + MSTKERR + MSTKERR + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + MMARVALID + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Bus fault address + 0 + 32 + + + + + + + PF + Processor features + PF + 0xE000ED78 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + + CLIDR + CLIDR + Cache Level ID register + 0x0 + 0x20 + read-only + 0x09000003 + + + CL1 + CL1 + 0 + 3 + + + CL2 + CL2 + 3 + 3 + + + CL3 + CL3 + 6 + 3 + + + CL4 + CL4 + 9 + 3 + + + CL5 + CL5 + 12 + 3 + + + CL6 + CL6 + 15 + 3 + + + CL7 + CL7 + 18 + 3 + + + LoUIS + LoUIS + 21 + 3 + + + LoC + LoC + 24 + 3 + + + LoU + LoU + 27 + 3 + + + + + CTR + CTR + Cache Type register + 0x4 + 0x20 + read-only + 0X8303C003 + + + _IminLine + IminLine + 0 + 4 + + + DMinLine + DMinLine + 16 + 4 + + + ERG + ERG + 20 + 4 + + + CWG + CWG + 24 + 4 + + + Format + Format + 29 + 3 + + + + + CCSIDR + CCSIDR + Cache Size ID register + 0x8 + 0x20 + read-only + 0X00000000 + + + LineSize + LineSize + 0 + 3 + + + Associativity + Associativity + 3 + 10 + + + NumSets + NumSets + 13 + 15 + + + WA + WA + 28 + 1 + + + RA + RA + 29 + 1 + + + WB + WB + 30 + 1 + + + WT + WT + 31 + 1 + + + + + + + AC + Access control + AC + 0xE000EF90 + + 0x0 + 0x1D + registers + + + + ITCMCR + ITCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x0 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + DTCMCR + DTCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x4 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + AHBPCR + AHBPCR + AHBP Control register + 0x8 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + SZ + SZ + 1 + 3 + + + + + CACR + CACR + Auxiliary Cache Control + register + 0xC + 0x20 + read-write + 0X00000000 + + + SIWT + SIWT + 0 + 1 + + + ECCEN + ECCEN + 1 + 1 + + + FORCEWT + FORCEWT + 2 + 1 + + + + + AHBSCR + AHBSCR + AHB Slave Control register + 0x10 + 0x20 + read-write + 0X00000000 + + + CTL + CTL + 0 + 2 + + + TPRI + TPRI + 2 + 9 + + + INITCOUNT + INITCOUNT + 11 + 5 + + + + + ABFSR + ABFSR + Auxiliary Bus Fault Status + register + 0x18 + 0x20 + read-write + 0X00000000 + + + ITCM + ITCM + 0 + 1 + + + DTCM + DTCM + 1 + 1 + + + AHBP + AHBP + 2 + 1 + + + AXIM + AXIM + 3 + 1 + + + EPPB + EPPB + 4 + 1 + + + AXIMTYPE + AXIMTYPE + 8 + 2 + + + + + + + diff --git a/make/svd.mk b/make/svd.mk new file mode 100644 index 00000000000..6f749b17ae7 --- /dev/null +++ b/make/svd.mk @@ -0,0 +1,32 @@ + +SVDFILE := $(TARGET_OBJ_DIR)/svd.svd +CLEAN_ARTIFACTS += $(SVDFILE) + +.PHONY: $(SVDFILE) + +ifeq ($(TARGET_MCU),STM32F303) +SVD := STM32F303 +else ifeq ($(TARGET_MCU),STM32F405) +SVD := STM32F405 +else ifeq ($(TARGET_MCU),STM32F411) +SVD := STM32F411 +else ifeq ($(TARGET_MCU),STM32F427) +SVD := STM32F427 +else ifeq ($(TARGET_MCU),STM32F446) +SVD := STM32F446 +else ifeq ($(TARGET_MCU),STM32F7X2RE) +SVD := STM32F7x2 +else ifeq ($(TARGET_MCU),STM32F7X5XE) +SVD := STM32F7x5 +else ifeq ($(TARGET_MCU),STM32F7X5XG) +SVD := STM32F7x5 +else ifeq ($(TARGET_MCU),STM32F7X5XI) +SVD := STM32F7x5 +else ifeq ($(TARGET_MCU),STM32F7X6XG) +SVD := STM32F7x6 +endif + +svd: .FORCE $(SVDFILE) +$(SVDFILE): $(ROOT)/dev/svd/$(SVD).svd + $(V1) mkdir -p $(dir $@) + $(V1) cat $< > $@ diff --git a/make/targets.mk b/make/targets.mk index 76b46722c98..6b1ed63bd27 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -26,18 +26,40 @@ ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) endif -ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) -$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?) +ifeq ($(filter $(TARGET),$(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) +$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?) endif ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -TARGET_MCU := STM32F3 -else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) -TARGET_MCU := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS))) -TARGET_MCU := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F1_TARGETS))) -TARGET_MCU := STM32F1 +TARGET_MCU := STM32F303 +TARGET_MCU_GROUP := STM32F3 +else ifeq ($(TARGET),$(filter $(TARGET), $(F405_TARGETS))) +TARGET_MCU := STM32F405 +TARGET_MCU_GROUP := STM32F4 +else ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) +TARGET_MCU := STM32F411 +TARGET_MCU_GROUP := STM32F4 +else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS))) +TARGET_MCU := STM32F427 +TARGET_MCU_GROUP := STM32F4 +else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS))) +TARGET_MCU := STM32F446 +TARGET_MCU_GROUP := STM32F4 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7X2RE_TARGETS))) +TARGET_MCU := STM32F7X2RE +TARGET_MCU_GROUP := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XE_TARGETS))) +TARGET_MCU := STM32F7X5XE +TARGET_MCU_GROUP := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XG_TARGETS))) +TARGET_MCU := STM32F7X5XG +TARGET_MCU_GROUP := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XI_TARGETS))) +TARGET_MCU := STM32F7X5XI +TARGET_MCU_GROUP := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F7X6XG_TARGETS))) +TARGET_MCU := STM32F7X6XG +TARGET_MCU_GROUP := STM32F7 else $(error Unknown target MCU specified.) endif From 5a2eba02a3c08d56ecb86ae69a9048e63a74ba43 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 4 Nov 2019 16:23:00 +0000 Subject: [PATCH 042/110] [DEVELOPMENT] Add example files for vscode --- dev/vscode/launch.json | 23 ++++++++++++++ dev/vscode/tasks.json | 70 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 93 insertions(+) create mode 100644 dev/vscode/launch.json create mode 100644 dev/vscode/tasks.json diff --git a/dev/vscode/launch.json b/dev/vscode/launch.json new file mode 100644 index 00000000000..55af041e7da --- /dev/null +++ b/dev/vscode/launch.json @@ -0,0 +1,23 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + "name": "Cortex Debug", + "cwd": "${workspaceRoot}", + "executable": "./obj/main/INAV_${config:TARGET}.elf", + "request": "launch", + "type": "cortex-debug", + "servertype": "openocd", + "device": "${config:TARGET}", + "configFiles": [ + "./obj/main/${config:TARGET}/openocd.cfg" + ], + "preLaunchCommands": ["monitor arm semihosting enable"], + "preLaunchTask": "openocd-debug-prepare", + "svdFile": "./obj/main/${config:TARGET}/svd.svd", + } + ] +} diff --git a/dev/vscode/tasks.json b/dev/vscode/tasks.json new file mode 100644 index 00000000000..449719d48c9 --- /dev/null +++ b/dev/vscode/tasks.json @@ -0,0 +1,70 @@ +{ + // See https://go.microsoft.com/fwlink/?LinkId=733558 + // for the documentation about the tasks.json format + "version": "2.0.0", + "options": { + "env": { + "TARGET": "${config:TARGET}", + "SEMIHOSTING": "${config:SEMIHOSTING}" + } + }, + "tasks": [ + { + "label": "hex", + "type": "shell", + "command": "make", "args": ["hex"], + "problemMatcher": "$gcc", + "group": { + "kind": "build", + "isDefault": true + }, + "presentation": { + "echo": true, + "reveal": "always", + "focus": false, + } + }, + { + "label": "elf", + "type": "shell", + "command": "make", "args": ["elf"], + "problemMatcher": "$gcc", + "group": "build", + "presentation": { + "echo": true, + "reveal": "always", + "focus": false, + } + }, + { + "label": "openocd-flash", + "type": "shell", + "command": "make", "args": ["openocd-flash"], + "dependsOn": "elf" + }, + { + "label": "clean", + "type": "shell", + "command": "make", "args": ["clean"], + "problemMatcher": [] + }, + { + "label": "svd", + "type": "shell", + "command": "make", "args": ["svd"], + "problemMatcher": [] + }, + { + "label": "openocd-cfg", + "type": "shell", + "command": "make", "args": ["openocd-cfg"], + "problemMatcher": [] + }, + { + "label": "openocd-debug-prepare", + "type": "shell", + "dependsOn": ["svd", "openocd-cfg", "openocd-flash"], + "problemMatcher": [] + } + ] +} From 849a68843271fbda1fa75d6828adc83741b71e1b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 4 Nov 2019 17:28:10 +0000 Subject: [PATCH 043/110] [LOG] Make sure logHasOutput() returns true when semihosting is enabled With semihosting there's always a log output. Without considering it, logIsEnabled() would return false with semihosting enabled but without additional log outputs. Found by @shellixyz --- src/main/common/log.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/common/log.c b/src/main/common/log.c index 07eda4c7394..284589ca6dc 100644 --- a/src/main/common/log.c +++ b/src/main/common/log.c @@ -137,7 +137,11 @@ static size_t logFormatPrefix(char *buf, const timeMs_t timeMs) static bool logHasOutput(void) { +#if defined(SEMIHOSTING) + return true; +#else return logPort || mspLogPort; +#endif } static bool logIsEnabled(logTopic_e topic, unsigned level) From ca0b111d7b0896641febe7f1ee17464bd5fac41f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 9 Dec 2019 16:48:54 +0000 Subject: [PATCH 044/110] [F411] Increase main clock speed to 96MHz 96MHz is still below the 100MHz maximum while still allowing to configure a 48MHz clock for USB --- src/main/target/system_stm32f4xx.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index 1c62dccf669..65add7cf710 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -413,11 +413,11 @@ uint32_t hse_value = HSE_VALUE; #endif /* STM32F401xx */ #if defined(STM32F410xx) || defined(STM32F411xE) -#define PLL_N 336 +#define PLL_N 192 /* SYSCLK = PLL_VCO / PLL_P */ -#define PLL_P 4 +#define PLL_P 2 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ -#define PLL_Q 7 +#define PLL_Q 4 #endif /* STM32F410xx || STM32F411xE */ /******************************************************************************/ From 63b439c25c630a994aaf4b3d4622653956170120 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 10 Dec 2019 14:50:28 +0000 Subject: [PATCH 045/110] [make] Fix incorrect target in group 1 --- make/targets.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/make/targets.mk b/make/targets.mk index 6b1ed63bd27..8b55dc28e60 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -64,7 +64,7 @@ else $(error Unknown target MCU specified.) endif -GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI KISSFC FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD +GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX From 78a37e1d6d97637d8b8b20f29fb40f8317ca3eca Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 10 Dec 2019 18:21:59 +0000 Subject: [PATCH 046/110] [OSD] Fix off-by-one in osdGridBufferClearGridRect() Bottom row and right column weren't properly cleared from the grid buffer. --- src/main/drivers/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/osd.c b/src/main/drivers/osd.c index 12f9e518401..418758f61ef 100644 --- a/src/main/drivers/osd.c +++ b/src/main/drivers/osd.c @@ -72,8 +72,8 @@ void osdGridBufferClearGridRect(int x, int y, int w, int h) osdGridBufferConstrainRect(&x, &y, &w, &h, OSD_CHARACTER_GRID_MAX_WIDTH, OSD_CHARACTER_GRID_MAX_HEIGHT); int maxX = x + w; int maxY = y + h; - for (int ii = x; ii < maxX + w; ii++) { - for (int jj = y; jj < maxY; jj++) { + for (int ii = x; ii <= maxX + w; ii++) { + for (int jj = y; jj <= maxY; jj++) { *osdCharacterGridBufferGetEntryPtr(ii, jj) = 0; } } From 0cee00dfd245a3c84ae003f42e249dd0ca35e164 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 10 Dec 2019 21:10:19 +0000 Subject: [PATCH 047/110] [FrSkyOSD] Cleanup log/debug messages Move the "FrSky OSD:" prefix to the macros, so we don't have to prepend it to each message. --- src/main/io/frsky_osd.c | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index 5a1e435ba48..719476204e9 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -43,8 +43,8 @@ #define FRSKY_OSD_INFO_INTERVAL_MS 1000 #define FRSKY_OSD_TRACE(fmt, ...) -#define FRSKY_OSD_DEBUG(fmt, ...) LOG_D(OSD, fmt, ##__VA_ARGS__) -#define FRSKY_OSD_ERROR(fmt, ...) LOG_E(OSD, fmt, ##__VA_ARGS__) +#define FRSKY_OSD_DEBUG(fmt, ...) LOG_D(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) +#define FRSKY_OSD_ERROR(fmt, ...) LOG_E(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) #define FRSKY_OSD_ASSERT(x) typedef enum @@ -389,7 +389,7 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t } const frskyOSDInfoResponse_t *resp = payload; if (resp->magic[0] != 'A' || resp->magic[1] != 'G' || resp->magic[2] != 'H') { - FRSKY_OSD_ERROR("Invalid magic number %x %x %x, expecting AGH", + FRSKY_OSD_ERROR("invalid magic number %x %x %x, expecting AGH", resp->magic[0], resp->magic[1], resp->magic[2]); return false; } @@ -400,7 +400,7 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t state.info.viewport.width = resp->pixelWidth; state.info.viewport.height = resp->pixelHeight; if (!state.initialized) { - FRSKY_OSD_DEBUG("FrSky OSD initialized. Version %u.%u.%u, pixels=%ux%u, grid=%ux%u", + FRSKY_OSD_DEBUG("initialized. Version %u.%u.%u, pixels=%ux%u, grid=%ux%u", resp->versionMajor, resp->versionMinor, resp->versionPatch, resp->pixelWidth, resp->pixelHeight, resp->gridColumns, resp->gridRows); state.initialized = true; @@ -525,12 +525,11 @@ static uint8_t frskyOSDEncodeAttr(textAttributes_t attr) bool frskyOSDInit(videoSystem_e videoSystem) { UNUSED(videoSystem); - FRSKY_OSD_TRACE("frskyOSDInit()"); // TODO: Use videoSystem to set the signal standard when // no input is detected. const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_FRSKY_OSD); if (portConfig) { - FRSKY_OSD_TRACE("FrSky OSD configured, trying to connect..."); + FRSKY_OSD_TRACE("configured, trying to connect..."); portOptions_t portOptions = 0; serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_FRSKY_OSD, NULL, NULL, FRSKY_OSD_BAUDRATE, From da4123986804dc3e1ab72cc4edd893d9ae2ea647 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 10 Dec 2019 21:11:40 +0000 Subject: [PATCH 048/110] [canvas] Use itoa() instead of sprintf() to generate strings for AHI itoa() should be noticeably faster --- src/main/io/osd_canvas.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 56793628832..5cdd572695c 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -34,7 +34,7 @@ #include "common/log.h" #include "common/maths.h" -#include "common/printf.h" +#include "common/typeconversion.h" #include "common/utils.h" #include "drivers/display.h" @@ -249,7 +249,7 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA int level = ii * 10; int absLevel = ABS(level); - tfp_snprintf(buf, sizeof(buf), "%d", absLevel); + itoa(absLevel, buf, 10); int pos = level * pixelsPerDegreeLevel; int charY = 9 - pos * 2; int cx = (absLevel >= 100 ? -1.5f : -1.0) * canvas->gridElementWidth; From f642d86ebc4fde2fb6b9e913930ba40f018026f8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 10 Dec 2019 21:18:19 +0000 Subject: [PATCH 049/110] [canvas] Severely reduce the amount of data sent out when drawing AHI - Instead of erasing exactly what was drawn, erase the whole AHI rect - Reduce max AHI refresh rate to 10Hz This makes both the AHI and the 3D model in the configurator smooth, although now as smooth as they could be. This is an interim solution until DMA for UART_TX is implemented. --- src/main/io/osd_canvas.c | 101 +++++++++++++++++++-------------------- 1 file changed, 49 insertions(+), 52 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 5cdd572695c..ba9cbc138e5 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -30,6 +30,7 @@ #if defined(USE_CANVAS) +#define AHI_MIN_DRAW_INTERVAL_MS 100 #define AHI_MAX_DRAW_INTERVAL_MS 1000 #include "common/log.h" @@ -125,18 +126,10 @@ void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, cons displayCanvasStrokeLineToPoint(canvas, -6, -7); } -static void osdDrawArtificialHorizonLevelLine(displayCanvas_t *canvas, int width, int pos, int margin, bool erase) +static void osdDrawArtificialHorizonLevelLine(displayCanvas_t *canvas, int width, int pos, int margin) { displayCanvasSetLineOutlineType(canvas, DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM); - if (erase) { - displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - displayCanvasSetLineOutlineColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - } else { - displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_WHITE); - displayCanvasSetLineOutlineColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); - } - int yoff = pos >= 0 ? 10 : -10; int yc = -pos - 1; int sz = width / 2; @@ -156,55 +149,59 @@ static void osdDrawArtificialHorizonLevelLine(displayCanvas_t *canvas, int width displayCanvasStrokeLineToPoint(canvas, sz, yc + yoff); } -static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchAngle, float rollAngle, bool erase) +static void osdArtificialHorizonRect(displayCanvas_t *canvas, int *lx, int *ty, int *w, int *h) +{ + *w = (OSD_AHI_WIDTH + 1) * canvas->gridElementWidth; + *h = OSD_AHI_HEIGHT * canvas->gridElementHeight; + + *lx = (canvas->width - *w) / 2; + *ty = (canvas->height - *h) / 2; +} + +static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchAngle, float rollAngle) { int barWidth = (OSD_AHI_WIDTH - 1) * canvas->gridElementWidth; int levelBarWidth = barWidth * (3.0/4); int crosshairMargin = 6; float pixelsPerDegreeLevel = 3.5f; - int maxWidth = (OSD_AHI_WIDTH + 1) * canvas->gridElementWidth; - int maxHeight = OSD_AHI_HEIGHT * canvas->gridElementHeight; int borderSize = 3; char buf[12]; - displayCanvasContextPush(canvas); + int lx; + int ty; + int maxWidth; + int maxHeight; + + osdArtificialHorizonRect(canvas, &lx, &ty, &maxWidth, &maxHeight); - int lx = (canvas->width - maxWidth) / 2; - int ty = (canvas->height - maxHeight) / 2; + displayCanvasContextPush(canvas); - if (!erase) { - int rx = lx + maxWidth; - int by = ty + maxHeight; + int rx = lx + maxWidth; + int by = ty + maxHeight; - displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); + displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); - displayCanvasMoveToPoint(canvas, lx, ty + borderSize); - displayCanvasStrokeLineToPoint(canvas, lx, ty); - displayCanvasStrokeLineToPoint(canvas, lx + borderSize, ty); + displayCanvasMoveToPoint(canvas, lx, ty + borderSize); + displayCanvasStrokeLineToPoint(canvas, lx, ty); + displayCanvasStrokeLineToPoint(canvas, lx + borderSize, ty); - displayCanvasMoveToPoint(canvas, rx, ty + borderSize); - displayCanvasStrokeLineToPoint(canvas, rx, ty); - displayCanvasStrokeLineToPoint(canvas, rx - borderSize, ty); + displayCanvasMoveToPoint(canvas, rx, ty + borderSize); + displayCanvasStrokeLineToPoint(canvas, rx, ty); + displayCanvasStrokeLineToPoint(canvas, rx - borderSize, ty); - displayCanvasMoveToPoint(canvas,lx, by - borderSize); - displayCanvasStrokeLineToPoint(canvas, lx, by); - displayCanvasStrokeLineToPoint(canvas, lx + borderSize, by); + displayCanvasMoveToPoint(canvas,lx, by - borderSize); + displayCanvasStrokeLineToPoint(canvas, lx, by); + displayCanvasStrokeLineToPoint(canvas, lx + borderSize, by); - displayCanvasMoveToPoint(canvas, rx, by - borderSize); - displayCanvasStrokeLineToPoint(canvas, rx, by); - displayCanvasStrokeLineToPoint(canvas, rx - borderSize, by); - } + displayCanvasMoveToPoint(canvas, rx, by - borderSize); + displayCanvasStrokeLineToPoint(canvas, rx, by); + displayCanvasStrokeLineToPoint(canvas, rx - borderSize, by); displayCanvasClipToRect(canvas, lx + 1, ty + 1, maxWidth - 2, maxHeight - 2); osdGridBufferClearPixelRect(canvas, lx, ty, maxWidth, maxHeight); - if (erase) { - displayCanvasSetStrokeAndFillColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - displayCanvasSetLineOutlineColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - } else { - displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_WHITE); - displayCanvasSetLineOutlineColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); - } + displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_WHITE); + displayCanvasSetLineOutlineColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); // The draw just the 5 bars closest to the current pitch level float pitchDegrees = RADIANS_TO_DEGREES(pitchAngle); @@ -231,7 +228,7 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA int pos = ii * 10 * pixelsPerDegreeLevel; int margin = (ii > 9 || ii < -9) ? 9 : 6; - osdDrawArtificialHorizonLevelLine(canvas, levelBarWidth, -pos, margin, erase); + osdDrawArtificialHorizonLevelLine(canvas, levelBarWidth, -pos, margin); } displayCanvasContextPop(canvas); @@ -255,11 +252,7 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA int cx = (absLevel >= 100 ? -1.5f : -1.0) * canvas->gridElementWidth; int px = cx + (pitchOffset + pos) * sx * 2; int py = -charY - (pitchOffset + pos) * (1 - sy) * 2; - if (erase) { - displayCanvasDrawStringMask(canvas, px, py, buf, DISPLAY_CANVAS_COLOR_TRANSPARENT, 0); - } else { - displayCanvasDrawString(canvas, px, py, buf, 0); - } + displayCanvasDrawString(canvas, px, py, buf, 0); } displayCanvasContextPop(canvas); } @@ -271,19 +264,23 @@ void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *can static float prevPitchAngle = 9999; static float prevRollAngle = 9999; - static timeMs_t nextDrawMs = 0; + static timeMs_t nextDrawMaxMs = 0; + static timeMs_t nextDrawMinMs = 0; timeMs_t now = millis(); - if (fabsf(prevPitchAngle - pitchAngle) > 0.01f || - fabsf(prevRollAngle - rollAngle) > 0.01f || - now > nextDrawMs) { + float totalError = fabsf(prevPitchAngle - pitchAngle) + fabsf(prevRollAngle - rollAngle); + if ((now > nextDrawMinMs && totalError > 0.05f)|| now > nextDrawMaxMs) { + + int x, y, w, h; + osdArtificialHorizonRect(canvas, &x, &y, &w, &h); + displayCanvasClearRect(canvas, x, y, w, h); - osdDrawArtificialHorizonShapes(canvas, prevPitchAngle, prevRollAngle, true); - osdDrawArtificialHorizonShapes(canvas, pitchAngle, rollAngle, false); + osdDrawArtificialHorizonShapes(canvas, pitchAngle, rollAngle); prevPitchAngle = pitchAngle; prevRollAngle = rollAngle; - nextDrawMs = now + AHI_MAX_DRAW_INTERVAL_MS; + nextDrawMinMs = now + AHI_MIN_DRAW_INTERVAL_MS; + nextDrawMaxMs = now + AHI_MAX_DRAW_INTERVAL_MS; } } From e6be989b82c62f80ebc052ad612145987d6bd3e1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Thu, 12 Dec 2019 22:43:32 +0000 Subject: [PATCH 050/110] [canvas] Fix roll direction in AHI Kudos to @OlivierC-FR for the heads up --- src/main/io/osd_canvas.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index ba9cbc138e5..5a4c310a353 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -212,7 +212,7 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA displayCanvasCtmTranslate(canvas, 0, pitchOffset); displayCanvasContextPush(canvas); - displayCanvasCtmRotate(canvas, -rollAngle); + displayCanvasCtmRotate(canvas, rollAngle); displayCanvasCtmTranslate(canvas, translateX, translateY); @@ -237,8 +237,8 @@ static void osdDrawArtificialHorizonShapes(displayCanvas_t *canvas, float pitchA displayCanvasCtmScale(canvas, 0.5f, 0.5f); // Draw line labels - float sx = sin_approx(-rollAngle); - float sy = cos_approx(rollAngle); + float sx = sin_approx(rollAngle); + float sy = cos_approx(-rollAngle); for (int ii = pitchCenter - 2; ii <= pitchCenter + 2; ii++) { if (ii == 0) { continue; From ee266b30f33c0fa0733d805d71eb7c9005e2e030 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 14 Dec 2019 16:17:37 +0100 Subject: [PATCH 051/110] Kakute F7 HDV --- src/main/target/KAKUTEF7/KAKUTEF7HDV.mk | 1 + src/main/target/KAKUTEF7/target.h | 3 +++ 2 files changed, 4 insertions(+) create mode 100644 src/main/target/KAKUTEF7/KAKUTEF7HDV.mk diff --git a/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk b/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk new file mode 100644 index 00000000000..d99ea879d89 --- /dev/null +++ b/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk @@ -0,0 +1 @@ +#KAKUTEF7HDV.mk file \ No newline at end of file diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 0b65e77e189..01984ed350a 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -113,9 +113,12 @@ #define SPI4_MOSI_PIN PE6 #define USE_OSD + +#ifndef KAKUTEF7HDV #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN +#endif #if defined(KAKUTEF7MINI) #define M25P16_CS_PIN SPI1_NSS_PIN From cbcd81931fabc494514dad070f64d1a7b5e49356 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 14 Dec 2019 16:19:47 +0100 Subject: [PATCH 052/110] Add HDV to release targets --- Makefile | 2 +- make/release.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index d87fea00f1c..9a5da202efe 100644 --- a/Makefile +++ b/Makefile @@ -132,7 +132,7 @@ GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 ALIENFLIGHTNGF7 PIXRACER YUPIF4 YUPIF4MINI YUPIF4R2 YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX GROUP_5_TARGETS := ASGARD32F7 CHEBUZZF3 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 -GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO +GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO GROUP_8_TARGETS := MATEKF765 GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) diff --git a/make/release.mk b/make/release.mk index a4ecbd534bf..2ee7a0c0a26 100644 --- a/make/release.mk +++ b/make/release.mk @@ -6,7 +6,7 @@ RELEASE_TARGETS += ALIENFLIGHTNGF7 RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 RELEASE_TARGETS += FF_F35_LIGHTNING FF_FORTINIF4 -RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI +RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL From 70cc988eeadde644a6988615694dbe9806ff1d52 Mon Sep 17 00:00:00 2001 From: MATEKSYS Date: Mon, 16 Dec 2019 12:24:17 +0800 Subject: [PATCH 053/110] Add MATEKF722PX target --- src/main/target/MATEKF722PX/config.c | 32 +++++ src/main/target/MATEKF722PX/target.c | 50 ++++++++ src/main/target/MATEKF722PX/target.h | 177 ++++++++++++++++++++++++++ src/main/target/MATEKF722PX/target.mk | 17 +++ 4 files changed, 276 insertions(+) create mode 100755 src/main/target/MATEKF722PX/config.c create mode 100755 src/main/target/MATEKF722PX/target.c create mode 100755 src/main/target/MATEKF722PX/target.h create mode 100755 src/main/target/MATEKF722PX/target.mk diff --git a/src/main/target/MATEKF722PX/config.c b/src/main/target/MATEKF722PX/config.c new file mode 100755 index 00000000000..4276d736b68 --- /dev/null +++ b/src/main/target/MATEKF722PX/config.c @@ -0,0 +1,32 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "io/piniobox.h" +#include "config/config_master.h" +#include "config/feature.h" +#include "io/serial.h" +#include "io/frsky_osd.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = 47; + pinioBoxConfigMutable()->permanentId[1] = 48; + + serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_FRSKY_OSD; +} \ No newline at end of file diff --git a/src/main/target/MATEKF722PX/target.c b/src/main/target/MATEKF722PX/target.c new file mode 100755 index 00000000000..927c77cfc6d --- /dev/null +++ b/src/main/target/MATEKF722PX/target.c @@ -0,0 +1,50 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include "platform.h" +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +const timerHardware_t timerHardware[] = { + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP2-1 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP2-1 D(2, 7, 7) + + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-2 D(1, 2, 5) + + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-7 D(1, 1, 3) + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 UP1-7 D(1, 6, 3) + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 UP1-6 D(1, 3, 2) + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 3, 6) + + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2, PPM + DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2, softserial1_tx + + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // Cam_ctrl reserved + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h new file mode 100755 index 00000000000..9c0be7255b0 --- /dev/null +++ b/src/main/target/MATEKF722PX/target.h @@ -0,0 +1,177 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "MF7P" +#define USBD_PRODUCT_STRING "MATEKF722PX" + +#define LED0 PA14 //Blue SWCLK +#define LED1 PA13 //Green SWDIO + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_ACC +#define USE_GYRO +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +#define USE_ACC_MPU6000 +#define USE_GYRO_MPU6000 +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PC4 + +#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP +#define ACC_MPU6000_ALIGN CW180_DEG_FLIP + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** SPI2 Flash *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PC3 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB12 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI2 +#define SDCARD_CS_PIN PC15 + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 //TX2 pad +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC0 +#define ADC_CHANNEL_4_PIN PA4 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PA15 // Power switch +#define PINIO2_PIN PB3 // Camera switch + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_SOFTSERIAL) +#define CURRENT_METER_SCALE 250 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 +#define USE_OSD +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR + +//#define USE_CAMERA_CONTROL +//#define CAMERA_CONTROL_PIN PB15 diff --git a/src/main/target/MATEKF722PX/target.mk b/src/main/target/MATEKF722PX/target.mk new file mode 100755 index 00000000000..6e4ae52c63a --- /dev/null +++ b/src/main/target/MATEKF722PX/target.mk @@ -0,0 +1,17 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += SDCARD VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_ak8975.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/pitotmeter_adc.c \ + From 1dc802c970c73db7dccc0b981381a89389028358 Mon Sep 17 00:00:00 2001 From: MATEKSYS Date: Mon, 16 Dec 2019 12:31:29 +0800 Subject: [PATCH 054/110] Add MATEKF722PX target --- src/main/target/MATEKF722PX/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKF722PX/config.c b/src/main/target/MATEKF722PX/config.c index 4276d736b68..34cd163fe84 100755 --- a/src/main/target/MATEKF722PX/config.c +++ b/src/main/target/MATEKF722PX/config.c @@ -29,4 +29,4 @@ void targetConfiguration(void) pinioBoxConfigMutable()->permanentId[1] = 48; serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_FRSKY_OSD; -} \ No newline at end of file +} From e9ef30f233e1e514d56099781cec34aa81fff42a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 16 Dec 2019 15:03:51 +0100 Subject: [PATCH 055/110] Add MATEKF722PX to release and build --- make/release.mk | 2 +- make/targets.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/make/release.mk b/make/release.mk index 36f85ebc26c..93a82e37c24 100644 --- a/make/release.mk +++ b/make/release.mk @@ -15,7 +15,7 @@ RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4 RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 -RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 +RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL diff --git a/make/targets.mk b/make/targets.mk index 8b55dc28e60..fc71fb93000 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -71,7 +71,7 @@ GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 +GROUP_8_TARGETS := MATEKF765 MATEKF722PX GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) ## targets-group-1 : build some targets From c3b870a74d7a611966a691df5cca00d7b346bcb6 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 17 Dec 2019 20:19:07 +0000 Subject: [PATCH 056/110] add MSC to SDCARD F4 / F7 targets --- src/main/target/ALIENFLIGHTNGF7/target.mk | 4 ++-- src/main/target/ANYFCF7/target.mk | 3 +-- src/main/target/BEEROTORF4/target.mk | 4 ++-- src/main/target/BLUEJAYF4/target.mk | 4 ++-- src/main/target/F4BY/target.mk | 4 ++-- src/main/target/FRSKYF4/target.mk | 2 +- src/main/target/KAKUTEF7/target.mk | 2 +- src/main/target/MATEKF405/target.mk | 2 +- src/main/target/MATEKF405SE/target.mk | 2 +- src/main/target/MATEKF722/target.mk | 3 +-- src/main/target/MATEKF722PX/target.mk | 3 +-- src/main/target/MATEKF722SE/target.mk | 3 +-- src/main/target/MATEKF765/target.mk | 3 +-- src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk | 2 +- src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk | 2 +- src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk | 2 +- src/main/target/OMNIBUSF4/target.mk | 2 +- src/main/target/OMNIBUSF7/target.mk | 4 ++-- src/main/target/SPRACINGF4EVO/target.mk | 4 ++-- src/main/target/SPRACINGF7DUAL/target.mk | 4 +--- 20 files changed, 26 insertions(+), 33 deletions(-) diff --git a/src/main/target/ALIENFLIGHTNGF7/target.mk b/src/main/target/ALIENFLIGHTNGF7/target.mk index 4beb04ddd82..7f806ad190c 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.mk +++ b/src/main/target/ALIENFLIGHTNGF7/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -15,4 +15,4 @@ TARGET_SRC = \ drivers/compass/compass_ist8308.c \ drivers/compass/compass_lis3mdl.c \ drivers/max7456.c \ - drivers/light_ws2811strip.c + drivers/light_ws2811strip.c diff --git a/src/main/target/ANYFCF7/target.mk b/src/main/target/ANYFCF7/target.mk index 9d26cbbb2bd..26d64b7bcad 100644 --- a/src/main/target/ANYFCF7/target.mk +++ b/src/main/target/ANYFCF7/target.mk @@ -1,5 +1,5 @@ F7X5XG_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -15,4 +15,3 @@ TARGET_SRC = \ drivers/compass/compass_lis3mdl.c \ drivers/light_ws2811strip.c \ drivers/max7456.c - diff --git a/src/main/target/BEEROTORF4/target.mk b/src/main/target/BEEROTORF4/target.mk index aaa180a4f8c..71ba33ec56d 100644 --- a/src/main/target/BEEROTORF4/target.mk +++ b/src/main/target/BEEROTORF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP SDCARD HIGHEND +FEATURES += VCP SDCARD HIGHEND MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ @@ -15,4 +15,4 @@ TARGET_SRC = \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ drivers/max7456.c \ - drivers/light_ws2811strip.c \ No newline at end of file + drivers/light_ws2811strip.c diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk index 45a97b49995..9244b2aeec6 100644 --- a/src/main/target/BLUEJAYF4/target.mk +++ b/src/main/target/BLUEJAYF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -13,4 +13,4 @@ TARGET_SRC = \ drivers/compass/compass_ist8308.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ No newline at end of file + drivers/light_ws2811strip.c diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk index e5221e515ea..d5a0a84c3c4 100644 --- a/src/main/target/F4BY/target.mk +++ b/src/main/target/F4BY/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -11,4 +11,4 @@ TARGET_SRC = \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ drivers/rangefinder/rangefinder_hcsr04.c \ - drivers/max7456.c \ No newline at end of file + drivers/max7456.c diff --git a/src/main/target/FRSKYF4/target.mk b/src/main/target/FRSKYF4/target.mk index 526c6d61878..43d1b37fe9b 100755 --- a/src/main/target/FRSKYF4/target.mk +++ b/src/main/target/FRSKYF4/target.mk @@ -1,6 +1,6 @@ F405_TARGETS += $(TARGET) -FEATURES = VCP SDCARD +FEATURES = VCP SDCARD MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk index 612199437ab..07e5ccfc947 100755 --- a/src/main/target/KAKUTEF7/target.mk +++ b/src/main/target/KAKUTEF7/target.mk @@ -2,7 +2,7 @@ F7X5XG_TARGETS += $(TARGET) ifeq ($(TARGET), KAKUTEF7MINI) FEATURES += VCP ONBOARDFLASH else -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC endif TARGET_SRC = \ diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk index a35fdfbc826..dd5ce7864a0 100755 --- a/src/main/target/MATEKF405/target.mk +++ b/src/main/target/MATEKF405/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/MATEKF405SE/target.mk b/src/main/target/MATEKF405SE/target.mk index 3a860b32837..8a0cc40ea76 100644 --- a/src/main/target/MATEKF405SE/target.mk +++ b/src/main/target/MATEKF405SE/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk index 730cfa99000..f221bb51ca9 100755 --- a/src/main/target/MATEKF722/target.mk +++ b/src/main/target/MATEKF722/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -15,4 +15,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/max7456.c \ drivers/pitotmeter_adc.c \ - diff --git a/src/main/target/MATEKF722PX/target.mk b/src/main/target/MATEKF722PX/target.mk index 6e4ae52c63a..5c061571fb6 100755 --- a/src/main/target/MATEKF722PX/target.mk +++ b/src/main/target/MATEKF722PX/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -14,4 +14,3 @@ TARGET_SRC = \ drivers/compass/compass_lis3mdl.c \ drivers/light_ws2811strip.c \ drivers/pitotmeter_adc.c \ - diff --git a/src/main/target/MATEKF722SE/target.mk b/src/main/target/MATEKF722SE/target.mk index 71e499c0d93..63b91d30001 100644 --- a/src/main/target/MATEKF722SE/target.mk +++ b/src/main/target/MATEKF722SE/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -17,4 +17,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/max7456.c \ drivers/pitotmeter_adc.c \ - diff --git a/src/main/target/MATEKF765/target.mk b/src/main/target/MATEKF765/target.mk index d90bdab6b1b..11d75e59b31 100644 --- a/src/main/target/MATEKF765/target.mk +++ b/src/main/target/MATEKF765/target.mk @@ -1,5 +1,5 @@ F7X5XI_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -16,4 +16,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/max7456.c \ drivers/pitotmeter_adc.c \ - diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk index 7e8eafe084b..277ca008108 100755 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk +++ b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk @@ -1,2 +1,2 @@ # the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping -FEATURES = VCP SDCARD \ No newline at end of file +FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk index 4e7f4308fd5..3947ddaa4fb 100755 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk +++ b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk @@ -1,2 +1,2 @@ # the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping -FEATURES = VCP SDCARD \ No newline at end of file +FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk index d1b118b0db1..18df391c675 100755 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk +++ b/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk @@ -1,3 +1,3 @@ # OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, # except for an inverter on UART6. -FEATURES = VCP SDCARD +FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/target.mk b/src/main/target/OMNIBUSF4/target.mk index fa363a0f651..b6c11e7c820 100644 --- a/src/main/target/OMNIBUSF4/target.mk +++ b/src/main/target/OMNIBUSF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH SDCARD +FEATURES += VCP ONBOARDFLASH SDCARD MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/OMNIBUSF7/target.mk b/src/main/target/OMNIBUSF7/target.mk index 1fc43f1f964..30cffe44327 100644 --- a/src/main/target/OMNIBUSF7/target.mk +++ b/src/main/target/OMNIBUSF7/target.mk @@ -1,5 +1,5 @@ F7X5XG_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ @@ -15,4 +15,4 @@ TARGET_SRC = \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ drivers/light_ws2811strip.c \ - drivers/max7456.c \ No newline at end of file + drivers/max7456.c diff --git a/src/main/target/SPRACINGF4EVO/target.mk b/src/main/target/SPRACINGF4EVO/target.mk index 179fd78bc76..c586a9a0619 100755 --- a/src/main/target/SPRACINGF4EVO/target.mk +++ b/src/main/target/SPRACINGF4EVO/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES = VCP SDCARD +FEATURES = VCP SDCARD MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -14,5 +14,5 @@ TARGET_SRC = \ drivers/compass/compass_lis3mdl.c \ drivers/barometer/barometer_ms56xx.c \ drivers/light_ws2811strip.c \ - drivers/max7456.c + drivers/max7456.c # drivers/vtx_rtc6705.c diff --git a/src/main/target/SPRACINGF7DUAL/target.mk b/src/main/target/SPRACINGF7DUAL/target.mk index 47302073242..01a33f4d6f1 100644 --- a/src/main/target/SPRACINGF7DUAL/target.mk +++ b/src/main/target/SPRACINGF7DUAL/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES = VCP SDCARD +FEATURES = VCP SDCARD MSC TARGET_SRC = \ drivers/accgyro/accgyro_fake.c \ @@ -17,5 +17,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/max7456.c \ drivers/vtx_rtc6705_soft_spi.c - - From 9a7547df5e20e45579fe40837dfdd4519c3616f5 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 17 Dec 2019 21:56:44 +0000 Subject: [PATCH 057/110] 'fix' compilation for F7 --- src/main/drivers/usb_msc_f7xx.c | 3 ++- src/main/vcp_hal/usbd_desc.c | 3 +++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/usb_msc_f7xx.c b/src/main/drivers/usb_msc_f7xx.c index d688becfa6e..bf56fd7564d 100644 --- a/src/main/drivers/usb_msc_f7xx.c +++ b/src/main/drivers/usb_msc_f7xx.c @@ -49,7 +49,8 @@ #include "usbd_msc.h" #include "msc/usbd_storage.h" -USBD_HandleTypeDef USBD_Device; +// declared in drivers/serial_usb_vcp.c for F7 +extern USBD_HandleTypeDef USBD_Device; #define DEBOUNCE_TIME_MS 20 diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index e7eb0c4a982..bdad593bb11 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -46,11 +46,14 @@ */ /* Includes ------------------------------------------------------------------*/ +#include #include "usbd_core.h" #include "usbd_desc.h" #include "usbd_conf.h" #include "platform.h" #include "build/version.h" +#include "drivers/usb_msc.h" + /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ From f12c2307100cd0e06c50dd44f00b60e79724af09 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Wed, 18 Dec 2019 13:17:15 +0000 Subject: [PATCH 058/110] document MSC mode --- docs/Cli.md | 1 + docs/USB_Mass_Storage_(MSC)_mode.md | 74 +++++++++++++++++++++++++++++ 2 files changed, 75 insertions(+) create mode 100644 docs/USB_Mass_Storage_(MSC)_mode.md diff --git a/docs/Cli.md b/docs/Cli.md index 11c7fd08fca..2c196625d82 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -80,6 +80,7 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag | `led` | configure leds | | `map` | mapping of rc channel order | | `motor` | get/set motor output value | +| `msc` | Enter USB Mass storage mode. See docs/USB_Mass_Storage_(MSC)_mode.md for usage information.| | `play_sound` | index, or none for next | | `profile` | index (0 to 2) | | `rxrange` | configure rx channel ranges (end-points) | diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md new file mode 100644 index 00000000000..f81047ad685 --- /dev/null +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -0,0 +1,74 @@ +## Overview + +iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card access, meaning you can mount the FC (SD card) as an OS file system via USB to read BB logs (and delete them). + +## Usage + +To put the FC in MSC mode: + +* Enter the CLI +* Enter the CLI command `msc` ; the FC will reboot +* Close the CLI tool (`cliterm`, configurator etc.) +* Wait for the device to be recognised as USB storage device by the operating system (may take some time, 10-15 seconds perhaps). +* Copy files off the MSC mounted FC (sd card) (`cp`, file manager) +* Dismount / eject the FC (sd card) card using the standard OS method +* Power-cycle the FC to exit MSC mode. + +## Performance + +Reading is quite slow, typically c. 340kBs, for example: + +``` +#################### +## Using MSC mode ## +#################### +# FC is automounted to /run/media/jrh/BBOX-QUAD by the OS +$ rsync -P /run/media/jrh/BBOX-QUAD/LOGS/LOG00035.TXT /tmp/msclogs/ +LOG00035.TXT + 55,856,827 100% 339.15kB/s 0:02:40 (xfr#1, to-chk=0/1) +``` + +``` +######################### +## Using a card-reader ## +######################### +# SD Card is automounted to /run/media/jrh/BBOX-QUAD by the OS +$ rsync -P /run/media/jrh/BBOX-QUAD/LOGS/LOG00035.TXT /tmp/sdclogs/ +LOG00035.TXT + 55,856,827 100% 19.26MB/s 0:00:02 (xfr#1, to-chk=0/1) +``` +i.e c. 2.5 seconds for the card reader, 2 minutes 40 seconds for MSC (60 times slower). However, if the card is relatively inaccessible, this is a reasonable trade-off + +## Comparison and Integrity + +The same file (`LOG00035.TXT`, c 55MB) is copied by MSC to `/tmp/msclogs` and directly (SD Card Reader) to `/tmp/sdclogs`. + +``` +$ cmp /tmp/{msc,sdc}logs/LOG00035.TXT +# no differences reported ... +``` + +``` +$ md5sum /tmp/{msc,sdc}logs/LOG00035.TXT +7cd259777ba4f29ecbde2f76882b1840 /tmp/msclogs/LOG00035.TXT +7cd259777ba4f29ecbde2f76882b1840 /tmp/sdclogs/LOG00035.TXT +``` +You should also be able to run blackbox utilities (e.g. the iNav specific `blackbox_decode`) without errors on the files, e.g. + +``` +$ blackbox_decode --stdout --merge-gps > /dev/null /tmp/msclogs/LOG00035.TXT +Log 1 of 1, start 36:00.888, end 62:00.851, duration 25:59.963 + +Statistics +Looptime 1006 avg 9.2 std dev (0.9%) +I frames 48405 104.6 bytes avg 5062215 bytes total +P frames 726064 69.2 bytes avg 50246994 bytes total +H frames 380 10.0 bytes avg 3800 bytes total +G frames 15674 21.4 bytes avg 334701 bytes total +S frames 6198 33.0 bytes avg 204534 bytes total +Frames 774469 71.4 bytes avg 55309209 bytes total +Data rate 496Hz 35806 bytes/s 358100 baud + +3 frames failed to decode, rendering 4 loop iterations unreadable. 4 iterations are missing in total (4ms, 0.00%) +774472 loop iterations weren't logged because of your blackbox_rate settings (779980ms, 50.00%) +``` From d55a3592ca6aa0a33dc46f24960bec34b03ae235 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 19 Dec 2019 21:33:10 +0000 Subject: [PATCH 059/110] white space optimisation (awake slumbering travis) --- src/main/vcp_hal/usbd_desc.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index bdad593bb11..48806761364 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -54,7 +54,6 @@ #include "build/version.h" #include "drivers/usb_msc.h" - /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ #define USBD_VID 0x0483 From 223c8c6f9635e77121750b7298fae3e827364c98 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 19 Dec 2019 22:37:43 +0000 Subject: [PATCH 060/110] remove generic, common USE_USB_MSC, add to specific target files as required BY SDCARD capability --- src/main/target/ALIENFLIGHTNGF7/target.h | 1 + src/main/target/ANYFCF7/target.h | 1 + src/main/target/BEEROTORF4/target.h | 2 ++ src/main/target/BLUEJAYF4/target.h | 1 + src/main/target/F4BY/target.h | 1 + src/main/target/FRSKYF4/target.h | 2 ++ src/main/target/KAKUTEF7/target.h | 1 + src/main/target/MATEKF405/target.h | 2 ++ src/main/target/MATEKF405SE/target.h | 2 ++ src/main/target/MATEKF722/target.h | 2 ++ src/main/target/MATEKF722PX/target.h | 6 ++++-- src/main/target/MATEKF722SE/target.h | 5 +++-- src/main/target/MATEKF765/target.h | 1 + src/main/target/OMNIBUSF4/target.h | 1 + src/main/target/OMNIBUSF7/target.h | 3 ++- src/main/target/SPRACINGF7DUAL/target.h | 2 ++ src/main/target/common.h | 4 ---- 17 files changed, 28 insertions(+), 9 deletions(-) diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 116cf92d5f6..79da7cc3881 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -90,6 +90,7 @@ #define SDCARD_DETECT_PIN PB11 #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PB10 +#define USE_USB_MSC #define M25P16_CS_PIN SPI2_NSS_PIN #define M25P16_SPI_BUS BUS_SPI2 diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index 288c8136f27..749c88202bb 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -141,6 +141,7 @@ #define SDCARD_DETECT_PIN PD3 #define SDCARD_SPI_BUS BUS_SPI4 #define SDCARD_CS_PIN SPI4_NSS_PIN +#define USE_USB_MSC #define USE_I2C #define USE_I2C_DEVICE_4 diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index 1c11634ba83..165a2082ec4 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -74,6 +74,8 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN SPI2_NSS_PIN +#define USE_USB_MSC + #define USE_VCP #define VBUS_SENSING_ENABLED #define VBUS_SENSING_PIN PC5 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 92184c09309..64a68af4866 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -71,6 +71,7 @@ #define SDCARD_DETECT_PIN PD2 #define SDCARD_SPI_BUS BUS_SPI3 #define SDCARD_CS_PIN PA15 +#define USE_USB_MSC #define M25P16_CS_PIN PB7 #define M25P16_SPI_BUS BUS_SPI3 diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index bcdf88a1e8a..6da5a88b38d 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -65,6 +65,7 @@ #define USE_SDCARD_SPI #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PE15 +#define USE_USB_MSC #define USE_VCP #define VBUS_SENSING_PIN PA9 diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index b727701acee..08cbb1ed636 100755 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -56,6 +56,8 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN SPI2_NSS_PIN +#define USE_USB_MSC + #define USE_VCP #define VBUS_SENSING_PIN PC5 diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 0b65e77e189..f6b616e0620 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -130,6 +130,7 @@ #define SDCARD_CS_PIN SPI1_NSS_PIN #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PD8 +#define USE_USB_MSC #endif #define USE_I2C diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index df11ef86f74..79024c149c7 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -72,6 +72,8 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_USB_MSC + // *************** M25P256 flash ******************** #define USE_FLASHFS #define USE_FLASH_M25P16 diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 9c9cd393a0a..9d0a8727724 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -107,6 +107,8 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_USB_MSC + // *************** UART ***************************** #define USE_VCP #define VBUS_SENSING_PIN PC13 diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 51ef9cdf90c..ecd74c47e9c 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -88,6 +88,8 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_USB_MSC + // *************** OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index 9c0be7255b0..b2a1198c74e 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -21,7 +21,7 @@ #define TARGET_BOARD_IDENTIFIER "MF7P" #define USBD_PRODUCT_STRING "MATEKF722PX" -#define LED0 PA14 //Blue SWCLK +#define LED0 PA14 //Blue SWCLK #define LED1 PA13 //Green SWDIO #define BEEPER PC13 @@ -93,6 +93,8 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PC15 +#define USE_USB_MSC + // *************** UART ***************************** #define USE_VCP #define USB_DETECT_PIN PC14 @@ -121,7 +123,7 @@ #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 - + #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_TX_PIN PA2 //TX2 pad #define SOFTSERIAL_1_RX_PIN PA2 diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 28169a3ab1c..3d389463b8b 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -123,6 +123,7 @@ # define SDCARD_SPI_BUS BUS_SPI3 # define SDCARD_CS_PIN PD2 # define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +# define USE_USB_MSC #endif // *************** UART ***************************** @@ -149,7 +150,7 @@ #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 - + #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_TX_PIN PA2 #define SOFTSERIAL_1_RX_PIN PA2 @@ -198,4 +199,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT #define USE_SERIALSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index 5329c419ae3..0b4c8ce4bd7 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -168,6 +168,7 @@ #define SDCARD_SDIO_DMA DMA_TAG(2,3,4) #define SDCARD_SDIO_4BIT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define USE_USB_MSC // *************** ADC ***************************** #define USE_ADC diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 101d2d98ea3..4c619d29505 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -240,6 +240,7 @@ #define M25P16_SPI_BUS BUS_SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16 + #define USE_USB_MSC #endif #define USE_ADC diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index c3a72620783..a160dbe0c8e 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -148,6 +148,7 @@ #define SDCARD_DETECT_PIN PE3 #define SDCARD_SPI_BUS BUS_SPI4 #define SDCARD_CS_PIN SPI4_NSS_PIN +#define USE_USB_MSC #define USE_I2C #define USE_I2C_DEVICE_2 @@ -209,4 +210,4 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff -#define PCA9685_I2C_BUS BUS_I2C2 \ No newline at end of file +#define PCA9685_I2C_BUS BUS_I2C2 diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h index f114662c408..86faeea4338 100644 --- a/src/main/target/SPRACINGF7DUAL/target.h +++ b/src/main/target/SPRACINGF7DUAL/target.h @@ -155,6 +155,8 @@ #define SDCARD_SPI_BUS BUS_SPI3 #define SDCARD_CS_PIN PC3 +#define USE_USB_MSC + // disabled for motor outputs 5-8: //#define USE_VTX_RTC6705 //#define USE_VTX_RTC6705_SOFTSPI diff --git a/src/main/target/common.h b/src/main/target/common.h index c130c090917..8f1158ae849 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -44,10 +44,6 @@ #define SKIP_CLI_RESOURCES #endif -#if defined(STM32F4) || defined(STM32F7) -#define USE_USB_MSC -#endif - #define USE_ADC_AVERAGING #define USE_64BIT_TIME #define USE_BLACKBOX From 969565b9ad2ad72040c1508656c6ce61a21e8bef Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 11:07:31 +0000 Subject: [PATCH 061/110] fix up build; re-enable unconditional USE_USB_MSC for F4 / F7 and #undef for appropriate targets --- src/main/msc/emfat_file.c | 362 +++++++++++++--------- src/main/msc/usbd_storage_emfat.c | 2 +- src/main/target/AIRBOTF4/target.mk | 2 +- src/main/target/ALIENFLIGHTNGF7/target.h | 1 - src/main/target/ANYFC/target.h | 4 + src/main/target/ANYFCF7/target.h | 1 - src/main/target/ANYFCM7/target.mk_ | 2 +- src/main/target/ASGARD32F7/target.mk | 2 +- src/main/target/BEEROTORF4/target.h | 2 - src/main/target/BETAFLIGHTF4/target.mk | 2 +- src/main/target/BLUEJAYF4/target.h | 1 - src/main/target/CLRACINGF4AIR/target.h | 4 + src/main/target/COLIBRI/target.mk | 3 +- src/main/target/DALRCF405/target.mk | 3 +- src/main/target/F4BY/target.h | 1 - src/main/target/FF_F35_LIGHTNING/target.h | 4 + src/main/target/FF_FORTINIF4/target.mk | 4 +- src/main/target/FRSKYF4/target.h | 2 - src/main/target/FURYF4OSD/target.mk | 2 +- src/main/target/IFLIGHTF7_TWING/target.mk | 2 +- src/main/target/KAKUTEF7/target.h | 1 - src/main/target/MAMBAF405US/target.mk | 2 +- src/main/target/MATEKF405/target.h | 2 - src/main/target/MATEKF405SE/target.h | 2 - src/main/target/MATEKF411/target.h | 4 + src/main/target/MATEKF411SE/target.h | 4 + src/main/target/MATEKF722/target.h | 2 - src/main/target/MATEKF722PX/target.h | 6 +- src/main/target/MATEKF722SE/target.h | 5 +- src/main/target/MATEKF765/target.h | 1 - src/main/target/NOX/target.mk | 3 +- src/main/target/OMNIBUSF4/target.h | 1 - src/main/target/OMNIBUSF7/target.h | 3 +- src/main/target/OMNIBUSF7NXT/target.mk | 2 +- src/main/target/SPEEDYBEEF4/target.mk | 2 +- src/main/target/SPRACINGF7DUAL/target.h | 2 - src/main/target/common.h | 4 + 37 files changed, 254 insertions(+), 198 deletions(-) diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index d95a9e75a7d..5f7bf951550 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -38,7 +38,7 @@ static const char autorun_file[] = "[autorun]\r\n" "icon=icon.ico\r\n" - "label=Betaflight Onboard Flash\r\n" ; + "label=iNav Onboard Flash\r\n" ; #define AUTORUN_SIZE (sizeof(autorun_file) - 1) #define EMFAT_INCR_AUTORUN 1 #else @@ -55,156 +55,214 @@ static const char readme_file[] = #endif #ifdef USE_EMFAT_ICON -static const char icon_file[] = +static const unsigned char icon_file[] = { - 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x28, 0x09, - 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00, - 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0xfc, - 0xfc, 0xde, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, - 0xfb, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfc, 0xfc, - 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xde, 0xfb, 0xfb, - 0xfb, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xf4, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, - 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, - 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xfb, - 0xfc, 0xff, 0xd7, 0xdd, 0xe1, 0xff, 0xc7, 0xc3, 0xc2, 0xff, 0xce, 0xce, 0xce, 0xff, 0xe2, 0xe4, - 0xe5, 0xff, 0xfd, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, - 0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb0, 0xad, 0xad, 0xff, 0x3a, 0x89, - 0xa8, 0xff, 0x03, 0xb5, 0xed, 0xff, 0x20, 0x57, 0x6c, 0xff, 0x36, 0x25, 0x1f, 0xff, 0x34, 0x52, - 0x5e, 0xff, 0x4f, 0x65, 0x6e, 0xff, 0x8a, 0x86, 0x84, 0xff, 0xd8, 0xd8, 0xd8, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfa, 0xfa, - 0xfa, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, - 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb2, 0xb1, 0xff, 0x2a, 0x1d, 0x18, 0xff, 0x33, 0x2a, - 0x26, 0xff, 0x25, 0x68, 0x7f, 0xff, 0x16, 0x90, 0xbe, 0xff, 0x3a, 0x38, 0x37, 0xff, 0x37, 0x38, - 0x38, 0xff, 0x31, 0x35, 0x37, 0xff, 0x29, 0x28, 0x27, 0xff, 0x34, 0x34, 0x34, 0xff, 0x93, 0x93, - 0x93, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xfc, 0xf8, 0xff, 0x4f, 0xa0, 0xbf, 0xff, 0x0d, 0x8c, 0xb8, 0xff, 0x2c, 0x62, - 0x76, 0xff, 0x3e, 0x31, 0x2e, 0xff, 0x36, 0x46, 0x4d, 0xff, 0x38, 0x41, 0x44, 0xff, 0x3b, 0x39, - 0x38, 0xff, 0x37, 0x36, 0x35, 0xff, 0x2c, 0x2c, 0x2c, 0xff, 0x28, 0x28, 0x28, 0xff, 0x83, 0x83, - 0x83, 0xff, 0x77, 0x77, 0x77, 0xff, 0xd5, 0xd5, 0xd5, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, - 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xfd, 0xfb, 0xff, 0x5f, 0x98, 0xad, 0xff, 0x1a, 0x5c, 0x73, 0xff, 0x30, 0x5a, - 0x6a, 0xff, 0x38, 0x42, 0x46, 0xff, 0x3c, 0x35, 0x33, 0xff, 0x39, 0x38, 0x37, 0xff, 0x2b, 0x2b, - 0x2b, 0xff, 0x3c, 0x3c, 0x3c, 0xff, 0x83, 0x83, 0x83, 0xff, 0xc2, 0xc2, 0xc2, 0xff, 0xd2, 0xd2, - 0xd2, 0xff, 0xa9, 0xa9, 0xa9, 0xff, 0x86, 0x86, 0x86, 0xff, 0xdf, 0xdf, 0xdf, 0xee, 0xfc, 0xfc, - 0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc3, 0xba, 0xb7, 0xff, 0x2c, 0x21, 0x1d, 0xff, 0x38, 0x30, - 0x2d, 0xff, 0x3c, 0x3a, 0x39, 0xff, 0x34, 0x35, 0x35, 0xff, 0x2e, 0x2e, 0x2e, 0xff, 0x78, 0x78, - 0x78, 0xff, 0xdf, 0xdf, 0xdf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xeb, 0xeb, 0xeb, 0xee, 0xfa, 0xfa, - 0xfa, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, - 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb3, 0xb0, 0xaf, 0xff, 0x3d, 0x31, - 0x2c, 0xff, 0x33, 0x30, 0x2f, 0xff, 0x49, 0x4a, 0x4a, 0xff, 0xcb, 0xcb, 0xcb, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, - 0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd3, 0xe2, 0xe8, 0xff, 0x1c, 0x85, - 0xae, 0xff, 0x2f, 0x44, 0x4c, 0xff, 0x41, 0x3c, 0x3a, 0xff, 0x9a, 0x9a, 0x9a, 0xff, 0xf9, 0xf9, - 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xf5, 0xf5, - 0xf5, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0x8a, 0xd0, 0xea, 0xff, 0x00, 0xb0, - 0xf7, 0xff, 0x36, 0x49, 0x51, 0xff, 0x39, 0x33, 0x31, 0xff, 0x1f, 0x1f, 0x1f, 0xff, 0x98, 0x98, - 0x98, 0xff, 0xe2, 0xe2, 0xe2, 0xff, 0x9b, 0x9b, 0x9b, 0xff, 0x71, 0x71, 0x71, 0xff, 0x72, 0x72, - 0x72, 0xff, 0x63, 0x63, 0x63, 0xff, 0xef, 0xef, 0xef, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xf4, - 0xf4, 0xff, 0xae, 0xae, 0xae, 0xff, 0x8c, 0x8c, 0x8c, 0xff, 0x86, 0x86, 0x86, 0xff, 0x84, 0x84, - 0x84, 0xff, 0x86, 0x86, 0x86, 0xff, 0x91, 0x8a, 0x87, 0xff, 0x48, 0x7a, 0x8d, 0xff, 0x00, 0x9c, - 0xd7, 0xff, 0x3a, 0x3e, 0x3f, 0xff, 0x39, 0x36, 0x35, 0xff, 0x35, 0x35, 0x35, 0xff, 0x42, 0x42, - 0x42, 0xff, 0x3b, 0x3b, 0x3b, 0xff, 0x31, 0x31, 0x31, 0xff, 0x92, 0x92, 0x92, 0xff, 0x90, 0x90, - 0x90, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, - 0xfb, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xde, 0xde, 0xde, 0xff, 0x80, 0x80, - 0x80, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xe6, 0xe6, 0xe6, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xea, 0xea, 0xea, 0xff, 0x81, 0x80, 0x80, 0xff, 0x49, 0x42, 0x40, 0xff, 0x55, 0x8e, - 0xa3, 0xff, 0x1f, 0x5b, 0x72, 0xff, 0x35, 0x3a, 0x3c, 0xff, 0x43, 0x41, 0x41, 0xff, 0x35, 0x35, - 0x35, 0xff, 0x2a, 0x2a, 0x2a, 0xff, 0xbe, 0xbe, 0xbe, 0xff, 0xe8, 0xe8, 0xe8, 0xff, 0x6f, 0x6f, - 0x6f, 0xff, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, - 0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xf5, 0xf5, 0xf5, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xe0, 0xe0, - 0xe0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xb8, 0xb8, - 0xb8, 0xff, 0x7d, 0x7d, 0x7d, 0xff, 0xa3, 0xa3, 0xa3, 0xff, 0xd2, 0xd2, 0xd2, 0xff, 0x87, 0x7c, - 0x77, 0xff, 0x5a, 0x57, 0x55, 0xff, 0xca, 0xcb, 0xcb, 0xff, 0x82, 0x82, 0x82, 0xff, 0x23, 0x23, - 0x23, 0xff, 0x38, 0x38, 0x38, 0xff, 0x43, 0x43, 0x43, 0xff, 0x5d, 0x5d, 0x5d, 0xff, 0xd9, 0xd9, - 0xd9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xa1, 0xa1, 0xa1, 0xff, 0xb6, 0xb6, 0xb6, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xc7, 0xc7, - 0xc7, 0xff, 0xea, 0xea, 0xea, 0xff, 0xa6, 0xa6, 0xa6, 0xff, 0x60, 0x60, 0x60, 0xff, 0x9f, 0x9f, - 0x9f, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd1, 0xd1, 0xd1, 0xff, 0x4e, 0x4e, - 0x4e, 0xff, 0x29, 0x29, 0x29, 0xff, 0x73, 0x73, 0x73, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xec, 0xec, 0xec, 0xff, 0x90, 0x90, 0x90, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xf0, 0xf0, 0xf0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb7, - 0xb7, 0xff, 0x61, 0x61, 0x61, 0xff, 0x89, 0x89, 0x89, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xdc, 0xdc, 0xdc, 0xff, 0x99, 0x99, - 0x99, 0xff, 0xbc, 0xbc, 0xbc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0x98, 0x98, 0x98, 0xff, 0x9c, 0x9c, 0x9c, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc5, 0xc5, 0xc5, 0xff, 0x66, 0x66, 0x66, 0xff, 0x76, 0x76, - 0x76, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdd, 0xdd, 0xdd, 0xff, 0xcd, 0xcd, 0xcd, 0xff, 0xf7, 0xf7, - 0xf7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xda, 0xda, - 0xda, 0xee, 0x48, 0x48, 0x48, 0xff, 0x75, 0x75, 0x75, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd5, 0xd5, - 0xd5, 0xff, 0x72, 0x72, 0x72, 0xff, 0x6a, 0x6a, 0x6a, 0xff, 0xc8, 0xc8, 0xc8, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xeb, 0xeb, - 0xeb, 0xee, 0xaf, 0xaf, 0xaf, 0xff, 0xb0, 0xb0, 0xb0, 0xff, 0x8b, 0x8b, 0x8b, 0xff, 0x60, 0x60, - 0x60, 0xff, 0xb3, 0xb3, 0xb3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, - 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0x66, 0x66, 0x66, 0xff, 0x54, 0x54, 0x54, 0xff, 0xa0, 0xa0, 0xa0, 0xff, 0xfa, 0xfa, - 0xfa, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, - 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, - 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xce, 0xce, - 0xce, 0xee, 0x98, 0x98, 0x98, 0xff, 0xef, 0xef, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xf6, 0xf6, - 0xf6, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xf4, 0xfd, 0xfd, - 0xfd, 0xde, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, - 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xde, + 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, + 0x20, 0x00, 0x88, 0x09, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x01, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x3d, 0x0b, + 0x00, 0x00, 0x3d, 0x0b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xd2, 0x97, 0x2a, 0x0b, 0xce, 0x91, 0x26, 0x52, 0xce, 0x90, + 0x25, 0x6e, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xce, 0x90, + 0x25, 0x6d, 0xce, 0x90, 0x25, 0x6d, 0xcf, 0x91, 0x26, 0x44, 0xd5, 0x9d, + 0x2e, 0x04, 0xcc, 0x8d, 0x23, 0x5d, 0xcb, 0x8a, 0x21, 0xf0, 0xcb, 0x8a, + 0x20, 0xfd, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfc, 0xcb, 0x8a, + 0x20, 0xfc, 0xcb, 0x8a, 0x20, 0xfd, 0xcb, 0x8b, 0x21, 0xe0, 0xcd, 0x8e, + 0x23, 0x37, 0xcb, 0x8b, 0x21, 0x81, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, + 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xff, 0xcb, 0x8b, 0x21, 0xf9, 0xcb, 0x8b, + 0x21, 0x53, 0xcd, 0x8d, 0x23, 0x81, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, + 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, + 0x23, 0xff, 0xcc, 0x8d, 0x22, 0xff, 0xcc, 0x8c, 0x20, 0xff, 0xcc, 0x8d, + 0x21, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, + 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, + 0x23, 0xff, 0xcc, 0x8c, 0x21, 0xff, 0xcc, 0x8c, 0x20, 0xff, 0xcc, 0x8d, + 0x22, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, + 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xff, 0xcc, 0x8d, 0x23, 0xf8, 0xcc, 0x8d, + 0x23, 0x53, 0xce, 0x8f, 0x24, 0x81, 0xce, 0x8f, 0x24, 0xff, 0xce, 0x8f, + 0x24, 0xff, 0xce, 0x8f, 0x24, 0xff, 0xce, 0x8f, 0x24, 0xff, 0xcd, 0x8e, + 0x23, 0xff, 0xcf, 0x94, 0x33, 0xff, 0xd3, 0xa0, 0x4c, 0xff, 0xd2, 0x9c, + 0x44, 0xff, 0xcd, 0x90, 0x28, 0xff, 0xcd, 0x8f, 0x23, 0xff, 0xce, 0x8f, + 0x24, 0xff, 0xce, 0x8f, 0x24, 0xff, 0xcd, 0x8f, 0x23, 0xff, 0xcd, 0x90, + 0x28, 0xff, 0xd2, 0x9c, 0x44, 0xff, 0xd3, 0xa0, 0x4c, 0xff, 0xcf, 0x94, + 0x33, 0xff, 0xcd, 0x8e, 0x23, 0xff, 0xce, 0x8f, 0x24, 0xff, 0xce, 0x8f, + 0x24, 0xff, 0xce, 0x8f, 0x24, 0xff, 0xce, 0x8f, 0x24, 0xf8, 0xcd, 0x8f, + 0x24, 0x53, 0xcf, 0x91, 0x26, 0x81, 0xcf, 0x91, 0x26, 0xff, 0xcf, 0x91, + 0x26, 0xff, 0xcf, 0x91, 0x26, 0xff, 0xce, 0x90, 0x24, 0xff, 0xd7, 0xa7, + 0x58, 0xff, 0xe7, 0xca, 0x9e, 0xff, 0xe4, 0xc4, 0x8d, 0xff, 0xe6, 0xc8, + 0x97, 0xff, 0xe2, 0xc1, 0x8b, 0xff, 0xd0, 0x97, 0x34, 0xff, 0xce, 0x91, + 0x25, 0xff, 0xce, 0x91, 0x25, 0xff, 0xd0, 0x97, 0x34, 0xff, 0xe2, 0xc1, + 0x8b, 0xff, 0xe6, 0xc8, 0x97, 0xff, 0xe4, 0xc4, 0x8d, 0xff, 0xe7, 0xca, + 0x9e, 0xff, 0xd7, 0xa7, 0x58, 0xff, 0xce, 0x90, 0x24, 0xff, 0xcf, 0x91, + 0x26, 0xff, 0xcf, 0x91, 0x26, 0xff, 0xcf, 0x91, 0x26, 0xf8, 0xcf, 0x91, + 0x26, 0x53, 0xd0, 0x93, 0x27, 0x81, 0xd0, 0x93, 0x27, 0xff, 0xd0, 0x93, + 0x27, 0xff, 0xcf, 0x93, 0x26, 0xff, 0xd4, 0x9e, 0x3f, 0xff, 0xe9, 0xcd, + 0xa0, 0xff, 0xd7, 0xa3, 0x47, 0xff, 0xcf, 0x93, 0x29, 0xff, 0xd0, 0x95, + 0x2b, 0xff, 0xe1, 0xbb, 0x78, 0xff, 0xe2, 0xbe, 0x82, 0xff, 0xcf, 0x93, + 0x27, 0xff, 0xcf, 0x93, 0x27, 0xff, 0xe2, 0xbe, 0x82, 0xff, 0xe1, 0xbb, + 0x78, 0xff, 0xd0, 0x95, 0x2b, 0xff, 0xcf, 0x93, 0x29, 0xff, 0xd7, 0xa3, + 0x47, 0xff, 0xe9, 0xcd, 0xa0, 0xff, 0xd4, 0x9e, 0x3f, 0xff, 0xcf, 0x92, + 0x26, 0xff, 0xd0, 0x93, 0x27, 0xff, 0xd0, 0x93, 0x27, 0xf8, 0xd0, 0x93, + 0x27, 0x53, 0xd1, 0x95, 0x29, 0x81, 0xd1, 0x95, 0x29, 0xff, 0xd1, 0x95, + 0x29, 0xff, 0xd0, 0x93, 0x25, 0xff, 0xde, 0xb3, 0x68, 0xff, 0xe2, 0xbd, + 0x7c, 0xff, 0xd2, 0x99, 0x32, 0xff, 0xea, 0xd1, 0xaa, 0xff, 0xde, 0xb6, + 0x70, 0xff, 0xd3, 0x9b, 0x35, 0xff, 0xe8, 0xcd, 0x9c, 0xff, 0xd3, 0x9a, + 0x33, 0xff, 0xd3, 0x9a, 0x33, 0xff, 0xe8, 0xcd, 0x9c, 0xff, 0xd3, 0x9b, + 0x35, 0xff, 0xde, 0xb6, 0x70, 0xff, 0xea, 0xd1, 0xaa, 0xff, 0xd2, 0x99, + 0x32, 0xff, 0xe2, 0xbd, 0x7c, 0xff, 0xde, 0xb3, 0x68, 0xff, 0xd0, 0x93, + 0x25, 0xff, 0xd1, 0x95, 0x29, 0xff, 0xd1, 0x95, 0x29, 0xf8, 0xd1, 0x95, + 0x29, 0x53, 0xd2, 0x97, 0x2a, 0x81, 0xd2, 0x97, 0x2a, 0xff, 0xd2, 0x97, + 0x2a, 0xff, 0xd1, 0x95, 0x27, 0xff, 0xdf, 0xb5, 0x69, 0xff, 0xe2, 0xbe, + 0x7d, 0xff, 0xd3, 0x9b, 0x33, 0xff, 0xee, 0xd7, 0xad, 0xff, 0xed, 0xd8, + 0xb4, 0xff, 0xd7, 0xa4, 0x4a, 0xff, 0xe7, 0xca, 0x94, 0xff, 0xd4, 0x9e, + 0x3c, 0xff, 0xd4, 0x9e, 0x3c, 0xff, 0xe7, 0xca, 0x94, 0xff, 0xd7, 0xa4, + 0x4a, 0xff, 0xed, 0xd8, 0xb4, 0xff, 0xee, 0xd7, 0xad, 0xff, 0xd3, 0x9b, + 0x33, 0xff, 0xe2, 0xbe, 0x7d, 0xff, 0xdf, 0xb5, 0x69, 0xff, 0xd1, 0x95, + 0x27, 0xff, 0xd2, 0x97, 0x2a, 0xff, 0xd2, 0x97, 0x2a, 0xf8, 0xd2, 0x97, + 0x2a, 0x53, 0xd3, 0x99, 0x2c, 0x81, 0xd3, 0x99, 0x2c, 0xff, 0xd3, 0x99, + 0x2c, 0xff, 0xd2, 0x98, 0x2a, 0xff, 0xd7, 0xa4, 0x43, 0xff, 0xea, 0xd0, + 0xa2, 0xff, 0xd7, 0xa4, 0x4a, 0xff, 0xd2, 0x98, 0x2d, 0xff, 0xdf, 0xb6, + 0x6a, 0xff, 0xe8, 0xcc, 0x9c, 0xff, 0xdb, 0xad, 0x5a, 0xff, 0xe7, 0xcb, + 0x9c, 0xff, 0xe7, 0xcb, 0x9c, 0xff, 0xdb, 0xad, 0x5a, 0xff, 0xe8, 0xcc, + 0x9c, 0xff, 0xdf, 0xb6, 0x6a, 0xff, 0xd2, 0x98, 0x2d, 0xff, 0xd7, 0xa5, + 0x4a, 0xff, 0xea, 0xd0, 0xa2, 0xff, 0xd7, 0xa4, 0x43, 0xff, 0xd2, 0x98, + 0x2a, 0xff, 0xd3, 0x99, 0x2c, 0xff, 0xd3, 0x99, 0x2c, 0xf8, 0xd3, 0x99, + 0x2c, 0x53, 0xd4, 0x9a, 0x2d, 0x81, 0xd4, 0x9b, 0x2d, 0xff, 0xd4, 0x9b, + 0x2d, 0xff, 0xd4, 0x9a, 0x2d, 0xff, 0xd3, 0x9a, 0x2c, 0xff, 0xde, 0xb2, + 0x5d, 0xff, 0xe9, 0xcf, 0xa1, 0xff, 0xe5, 0xc6, 0x93, 0xff, 0xe0, 0xba, + 0x77, 0xff, 0xdb, 0xac, 0x53, 0xff, 0xe2, 0xbe, 0x7d, 0xff, 0xfd, 0xfc, + 0xfa, 0xff, 0xfd, 0xfc, 0xfa, 0xff, 0xe2, 0xbe, 0x7d, 0xff, 0xdb, 0xac, + 0x53, 0xff, 0xe0, 0xba, 0x77, 0xff, 0xe5, 0xc6, 0x93, 0xff, 0xe9, 0xcf, + 0xa1, 0xff, 0xde, 0xb2, 0x5d, 0xff, 0xd3, 0x9a, 0x2c, 0xff, 0xd4, 0x9b, + 0x2d, 0xff, 0xd4, 0x9b, 0x2d, 0xff, 0xd4, 0x9b, 0x2d, 0xf8, 0xd4, 0x9b, + 0x2d, 0x53, 0xd5, 0x9c, 0x2e, 0x81, 0xd5, 0x9c, 0x2e, 0xff, 0xd5, 0x9c, + 0x2e, 0xff, 0xd5, 0x9c, 0x2e, 0xff, 0xd5, 0x9c, 0x2e, 0xff, 0xd4, 0x9b, + 0x2d, 0xff, 0xd8, 0xa3, 0x3c, 0xff, 0xdd, 0xaf, 0x55, 0xff, 0xda, 0xa9, + 0x49, 0xff, 0xd7, 0xa2, 0x3e, 0xff, 0xf3, 0xe5, 0xcd, 0xff, 0xf6, 0xea, + 0xd1, 0xff, 0xf6, 0xea, 0xd1, 0xff, 0xf3, 0xe5, 0xcd, 0xff, 0xd7, 0xa2, + 0x3e, 0xff, 0xda, 0xa9, 0x49, 0xff, 0xdd, 0xaf, 0x55, 0xff, 0xd8, 0xa3, + 0x3c, 0xff, 0xd4, 0x9b, 0x2d, 0xff, 0xd5, 0x9c, 0x2e, 0xff, 0xd5, 0x9c, + 0x2e, 0xff, 0xd5, 0x9c, 0x2e, 0xff, 0xd5, 0x9c, 0x2e, 0xf8, 0xd5, 0x9c, + 0x2e, 0x53, 0xd6, 0x9e, 0x2f, 0x81, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, + 0x2f, 0xff, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, + 0x2f, 0xff, 0xd5, 0x9d, 0x2d, 0xff, 0xd4, 0x9b, 0x2a, 0xff, 0xd4, 0x9b, + 0x28, 0xff, 0xe0, 0xb6, 0x66, 0xff, 0xf2, 0xe1, 0xc1, 0xff, 0xd9, 0xa6, + 0x40, 0xff, 0xd9, 0xa6, 0x40, 0xff, 0xf2, 0xe1, 0xc1, 0xff, 0xe0, 0xb6, + 0x66, 0xff, 0xd4, 0x9b, 0x28, 0xff, 0xd4, 0x9b, 0x2a, 0xff, 0xd5, 0x9d, + 0x2d, 0xff, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, + 0x2f, 0xff, 0xd6, 0x9e, 0x2f, 0xff, 0xd6, 0x9e, 0x2f, 0xf8, 0xd6, 0x9e, + 0x2f, 0x53, 0xd7, 0xa0, 0x31, 0x81, 0xd7, 0xa0, 0x31, 0xff, 0xd7, 0xa0, + 0x31, 0xff, 0xd7, 0xa0, 0x31, 0xff, 0xd6, 0xa0, 0x30, 0xff, 0xd6, 0x9f, + 0x31, 0xff, 0xda, 0xac, 0x54, 0xff, 0xe0, 0xba, 0x75, 0xff, 0xdc, 0xb1, + 0x5f, 0xff, 0xe1, 0xb9, 0x69, 0xff, 0xf0, 0xdd, 0xba, 0xff, 0xd6, 0xa1, + 0x37, 0xff, 0xd6, 0xa1, 0x37, 0xff, 0xf0, 0xdd, 0xba, 0xff, 0xe1, 0xb9, + 0x69, 0xff, 0xdc, 0xb1, 0x5f, 0xff, 0xe0, 0xba, 0x75, 0xff, 0xda, 0xac, + 0x54, 0xff, 0xd6, 0x9f, 0x31, 0xff, 0xd6, 0xa0, 0x30, 0xff, 0xd6, 0xa0, + 0x31, 0xff, 0xd6, 0x9f, 0x31, 0xff, 0xd7, 0xa0, 0x31, 0xf8, 0xd7, 0xa0, + 0x31, 0x53, 0xd7, 0xa1, 0x32, 0x81, 0xd7, 0xa1, 0x32, 0xff, 0xd7, 0xa1, + 0x32, 0xff, 0xd7, 0xa1, 0x32, 0xff, 0xd7, 0xa1, 0x32, 0xff, 0xe2, 0xbe, + 0x79, 0xff, 0xeb, 0xd1, 0xa0, 0xff, 0xe5, 0xc2, 0x79, 0xff, 0xe1, 0xb9, + 0x6a, 0xff, 0xe2, 0xbf, 0x7c, 0xff, 0xf0, 0xdd, 0xba, 0xff, 0xed, 0xd8, + 0xb3, 0xff, 0xed, 0xd8, 0xb3, 0xff, 0xf0, 0xdd, 0xba, 0xff, 0xe2, 0xbf, + 0x7c, 0xff, 0xe1, 0xb9, 0x6a, 0xff, 0xe5, 0xc1, 0x79, 0xff, 0xeb, 0xd1, + 0xa0, 0xff, 0xe2, 0xbe, 0x79, 0xff, 0xd7, 0xa1, 0x32, 0xff, 0xd7, 0xa1, + 0x32, 0xff, 0xd7, 0xa1, 0x32, 0xff, 0xd7, 0xa1, 0x32, 0xf8, 0xd7, 0xa1, + 0x32, 0x53, 0xd8, 0xa2, 0x33, 0x81, 0xd8, 0xa2, 0x33, 0xff, 0xd8, 0xa2, + 0x33, 0xff, 0xd8, 0xa2, 0x31, 0xff, 0xdd, 0xb0, 0x53, 0xff, 0xec, 0xd3, + 0xa1, 0xff, 0xda, 0xa8, 0x3f, 0xff, 0xd8, 0xa5, 0x40, 0xff, 0xe5, 0xc4, + 0x87, 0xff, 0xe9, 0xcd, 0x94, 0xff, 0xe3, 0xbf, 0x78, 0xff, 0xe4, 0xc0, + 0x75, 0xff, 0xe4, 0xc0, 0x75, 0xff, 0xe3, 0xbe, 0x78, 0xff, 0xe9, 0xcd, + 0x94, 0xff, 0xe5, 0xc4, 0x87, 0xff, 0xd8, 0xa5, 0x40, 0xff, 0xda, 0xa8, + 0x3f, 0xff, 0xec, 0xd3, 0xa1, 0xff, 0xdd, 0xb0, 0x53, 0xff, 0xd8, 0xa2, + 0x31, 0xff, 0xd8, 0xa2, 0x33, 0xff, 0xd8, 0xa2, 0x33, 0xf8, 0xd8, 0xa2, + 0x33, 0x53, 0xd9, 0xa4, 0x34, 0x81, 0xd9, 0xa4, 0x34, 0xff, 0xd9, 0xa4, + 0x34, 0xff, 0xd8, 0xa2, 0x30, 0xff, 0xe4, 0xbf, 0x73, 0xff, 0xe6, 0xc4, + 0x7d, 0xff, 0xda, 0xa9, 0x40, 0xff, 0xf3, 0xe5, 0xcc, 0xff, 0xf0, 0xdc, + 0xb3, 0xff, 0xdc, 0xab, 0x45, 0xff, 0xeb, 0xd2, 0x9e, 0xff, 0xda, 0xa8, + 0x3d, 0xff, 0xda, 0xa8, 0x3d, 0xff, 0xeb, 0xd2, 0x9e, 0xff, 0xdc, 0xab, + 0x45, 0xff, 0xf0, 0xdc, 0xb3, 0xff, 0xf3, 0xe5, 0xcc, 0xff, 0xda, 0xa9, + 0x40, 0xff, 0xe6, 0xc4, 0x7d, 0xff, 0xe4, 0xc0, 0x73, 0xff, 0xd8, 0xa2, + 0x30, 0xff, 0xd9, 0xa4, 0x34, 0xff, 0xd9, 0xa4, 0x34, 0xf8, 0xd9, 0xa4, + 0x34, 0x53, 0xd9, 0xa5, 0x35, 0x81, 0xd9, 0xa5, 0x35, 0xff, 0xd9, 0xa5, + 0x35, 0xff, 0xd9, 0xa4, 0x32, 0xff, 0xe3, 0xbc, 0x6a, 0xff, 0xe8, 0xc9, + 0x8b, 0xff, 0xda, 0xa7, 0x39, 0xff, 0xe9, 0xcb, 0x8a, 0xff, 0xe2, 0xb9, + 0x60, 0xff, 0xdc, 0xac, 0x47, 0xff, 0xec, 0xd3, 0xa1, 0xff, 0xdb, 0xa9, + 0x3c, 0xff, 0xdb, 0xa8, 0x3d, 0xff, 0xec, 0xd3, 0xa1, 0xff, 0xdc, 0xac, + 0x47, 0xff, 0xe2, 0xb9, 0x60, 0xff, 0xe9, 0xcb, 0x8a, 0xff, 0xda, 0xa7, + 0x39, 0xff, 0xe8, 0xc9, 0x8c, 0xff, 0xe3, 0xbc, 0x6a, 0xff, 0xd9, 0xa4, + 0x32, 0xff, 0xd9, 0xa5, 0x35, 0xff, 0xd9, 0xa5, 0x35, 0xf8, 0xd9, 0xa5, + 0x35, 0x53, 0xda, 0xa6, 0x35, 0x81, 0xda, 0xa6, 0x36, 0xff, 0xda, 0xa6, + 0x35, 0xff, 0xda, 0xa6, 0x35, 0xff, 0xdc, 0xac, 0x42, 0xff, 0xec, 0xd4, + 0xa2, 0xff, 0xe1, 0xb9, 0x6b, 0xff, 0xd9, 0xa6, 0x3c, 0xff, 0xdb, 0xaa, + 0x47, 0xff, 0xe9, 0xcc, 0x95, 0xff, 0xe6, 0xc4, 0x7a, 0xff, 0xda, 0xa5, + 0x34, 0xff, 0xda, 0xa5, 0x34, 0xff, 0xe6, 0xc4, 0x79, 0xff, 0xe9, 0xcc, + 0x95, 0xff, 0xdb, 0xaa, 0x47, 0xff, 0xd9, 0xa6, 0x3c, 0xff, 0xe1, 0xb9, + 0x6b, 0xff, 0xec, 0xd4, 0xa2, 0xff, 0xdc, 0xac, 0x42, 0xff, 0xda, 0xa6, + 0x35, 0xff, 0xda, 0xa6, 0x35, 0xff, 0xda, 0xa6, 0x36, 0xf8, 0xda, 0xa6, + 0x35, 0x53, 0xdb, 0xa7, 0x36, 0x81, 0xdb, 0xa7, 0x36, 0xff, 0xdb, 0xa7, + 0x36, 0xff, 0xdb, 0xa7, 0x36, 0xff, 0xda, 0xa7, 0x35, 0xff, 0xdf, 0xb2, + 0x50, 0xff, 0xeb, 0xd0, 0x97, 0xff, 0xeb, 0xd2, 0xa1, 0xff, 0xec, 0xd3, + 0xa2, 0xff, 0xe7, 0xc5, 0x7b, 0xff, 0xdb, 0xa9, 0x3a, 0xff, 0xdb, 0xa7, + 0x36, 0xff, 0xdb, 0xa7, 0x36, 0xff, 0xdb, 0xa9, 0x3a, 0xff, 0xe7, 0xc5, + 0x7b, 0xff, 0xec, 0xd3, 0xa2, 0xff, 0xeb, 0xd2, 0xa1, 0xff, 0xeb, 0xd0, + 0x97, 0xff, 0xdf, 0xb2, 0x50, 0xff, 0xda, 0xa7, 0x35, 0xff, 0xdb, 0xa7, + 0x36, 0xff, 0xdb, 0xa7, 0x36, 0xff, 0xdb, 0xa7, 0x36, 0xf8, 0xdb, 0xa7, + 0x36, 0x53, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa7, + 0x36, 0xff, 0xdb, 0xa9, 0x39, 0xff, 0xde, 0xae, 0x44, 0xff, 0xdd, 0xac, + 0x40, 0xff, 0xdb, 0xa7, 0x35, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa7, + 0x35, 0xff, 0xdd, 0xac, 0x40, 0xff, 0xde, 0xae, 0x44, 0xff, 0xdb, 0xa9, + 0x39, 0xff, 0xdb, 0xa7, 0x36, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xf8, 0xdb, 0xa8, + 0x37, 0x53, 0xdb, 0xa8, 0x37, 0x82, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x36, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x36, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xf8, 0xdb, 0xa8, + 0x37, 0x54, 0xdb, 0xa8, 0x37, 0x63, 0xdb, 0xa8, 0x37, 0xf6, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, + 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xff, 0xdb, 0xa8, 0x37, 0xe7, 0xdb, 0xa8, + 0x37, 0x3c, 0xdb, 0xa8, 0x37, 0x10, 0xdb, 0xa8, 0x37, 0x63, 0xdb, 0xa8, + 0x37, 0x82, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, + 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x81, 0xdb, 0xa8, 0x37, 0x53, 0xdb, 0xa8, + 0x37, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00 }; #define ICON_SIZE (sizeof(icon_file)) @@ -253,7 +311,7 @@ static const emfat_entry_t entriesPredefined[] = #ifdef USE_EMFAT_README { "readme.txt", false, 0, 1, 0, README_SIZE, 1024*1024, (long)readme_file, CMA, memory_read_proc, NULL, { 0 } }, #endif - { "BTFL_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } }, + { "INAV_LOG.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } }, }; #define ENTRY_INDEX_BBL (1 + EMFAT_INCR_AUTORUN + EMFAT_INCR_ICON + EMFAT_INCR_README) @@ -268,7 +326,7 @@ emfat_t emfat; static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uint32_t size) { - tfp_sprintf(logNames[number], "BTFL_%03d.BBL", number); + tfp_sprintf(logNames[number], "INAV_%03d.BBL", number); entry->name = logNames[number]; entry->level = 1; entry->offset = offset; diff --git a/src/main/msc/usbd_storage_emfat.c b/src/main/msc/usbd_storage_emfat.c index 096cf8a4b37..2257a404db2 100644 --- a/src/main/msc/usbd_storage_emfat.c +++ b/src/main/msc/usbd_storage_emfat.c @@ -54,7 +54,7 @@ static const uint8_t STORAGE_Inquirydata[] = (USBD_STD_INQUIRY_LENGTH - 5), #endif 0x00, 0x00, 0x00, - 'B', 'E', 'T', 'A', 'F', 'L', 'T', ' ', // Manufacturer : 8 bytes + 'I', 'N', 'A', 'V', ' ', 'F', 'C', ' ', // Manufacturer : 8 bytes 'O', 'n', 'b', 'o', 'a', 'r', 'd', ' ', // Product : 16 Bytes 'F', 'l', 'a', 's', 'h', ' ', ' ', ' ', // ' ', ' ', ' ' ,' ', // Version : 4 Bytes diff --git a/src/main/target/AIRBOTF4/target.mk b/src/main/target/AIRBOTF4/target.mk index 3c0b675157a..8c881ea99f8 100644 --- a/src/main/target/AIRBOTF4/target.mk +++ b/src/main/target/AIRBOTF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 79da7cc3881..116cf92d5f6 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -90,7 +90,6 @@ #define SDCARD_DETECT_PIN PB11 #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PB10 -#define USE_USB_MSC #define M25P16_CS_PIN SPI2_NSS_PIN #define M25P16_SPI_BUS BUS_SPI2 diff --git a/src/main/target/ANYFC/target.h b/src/main/target/ANYFC/target.h index 1cf7698c36a..6959a3856be 100644 --- a/src/main/target/ANYFC/target.h +++ b/src/main/target/ANYFC/target.h @@ -136,3 +136,7 @@ #define TARGET_IO_PORTD 0xffff #define PCA9685_I2C_BUS BUS_I2C2 + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index 749c88202bb..288c8136f27 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -141,7 +141,6 @@ #define SDCARD_DETECT_PIN PD3 #define SDCARD_SPI_BUS BUS_SPI4 #define SDCARD_CS_PIN SPI4_NSS_PIN -#define USE_USB_MSC #define USE_I2C #define USE_I2C_DEVICE_4 diff --git a/src/main/target/ANYFCM7/target.mk_ b/src/main/target/ANYFCM7/target.mk_ index 371bcd26da1..62211096bcc 100644 --- a/src/main/target/ANYFCM7/target.mk_ +++ b/src/main/target/ANYFCM7/target.mk_ @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/ASGARD32F7/target.mk b/src/main/target/ASGARD32F7/target.mk index a7615967053..2859009996d 100644 --- a/src/main/target/ASGARD32F7/target.mk +++ b/src/main/target/ASGARD32F7/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index 165a2082ec4..1c11634ba83 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -74,8 +74,6 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN SPI2_NSS_PIN -#define USE_USB_MSC - #define USE_VCP #define VBUS_SENSING_ENABLED #define VBUS_SENSING_PIN PC5 diff --git a/src/main/target/BETAFLIGHTF4/target.mk b/src/main/target/BETAFLIGHTF4/target.mk index a5826eef035..b1dfa5e503d 100755 --- a/src/main/target/BETAFLIGHTF4/target.mk +++ b/src/main/target/BETAFLIGHTF4/target.mk @@ -1,6 +1,6 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 64a68af4866..92184c09309 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -71,7 +71,6 @@ #define SDCARD_DETECT_PIN PD2 #define SDCARD_SPI_BUS BUS_SPI3 #define SDCARD_CS_PIN PA15 -#define USE_USB_MSC #define M25P16_CS_PIN PB7 #define M25P16_SPI_BUS BUS_SPI3 diff --git a/src/main/target/CLRACINGF4AIR/target.h b/src/main/target/CLRACINGF4AIR/target.h index afe073190d6..54955f2910d 100644 --- a/src/main/target/CLRACINGF4AIR/target.h +++ b/src/main/target/CLRACINGF4AIR/target.h @@ -150,3 +150,7 @@ #define TARGET_IO_PORTB (0xffff) #define TARGET_IO_PORTC (0xffff) #define TARGET_IO_PORTD BIT(2) + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/COLIBRI/target.mk b/src/main/target/COLIBRI/target.mk index 12b8887096f..133b6f3eb5d 100755 --- a/src/main/target/COLIBRI/target.mk +++ b/src/main/target/COLIBRI/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC HSE_VALUE = 16000000 TARGET_SRC = \ @@ -11,4 +11,3 @@ TARGET_SRC = \ drivers/compass/compass_ist8308.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c - diff --git a/src/main/target/DALRCF405/target.mk b/src/main/target/DALRCF405/target.mk index 69db30708ab..28cba8a0f1f 100644 --- a/src/main/target/DALRCF405/target.mk +++ b/src/main/target/DALRCF405/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -17,4 +17,3 @@ TARGET_SRC = \ drivers/pitotmeter_adc.c \ drivers/light_ws2811strip.c \ drivers/max7456.c - diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index 6da5a88b38d..bcdf88a1e8a 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -65,7 +65,6 @@ #define USE_SDCARD_SPI #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PE15 -#define USE_USB_MSC #define USE_VCP #define VBUS_SENSING_PIN PA9 diff --git a/src/main/target/FF_F35_LIGHTNING/target.h b/src/main/target/FF_F35_LIGHTNING/target.h index e50a43485d1..dec7d460e68 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.h +++ b/src/main/target/FF_F35_LIGHTNING/target.h @@ -144,3 +144,7 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/FF_FORTINIF4/target.mk b/src/main/target/FF_FORTINIF4/target.mk index 581916350df..4faee84af70 100644 --- a/src/main/target/FF_FORTINIF4/target.mk +++ b/src/main/target/FF_FORTINIF4/target.mk @@ -1,7 +1,7 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/max7456.c \ - drivers/light_ws2811strip.c \ No newline at end of file + drivers/light_ws2811strip.c diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 08cbb1ed636..b727701acee 100755 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -56,8 +56,6 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN SPI2_NSS_PIN -#define USE_USB_MSC - #define USE_VCP #define VBUS_SENSING_PIN PC5 diff --git a/src/main/target/FURYF4OSD/target.mk b/src/main/target/FURYF4OSD/target.mk index 654b3888b0a..0b76bb02356 100644 --- a/src/main/target/FURYF4OSD/target.mk +++ b/src/main/target/FURYF4OSD/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/IFLIGHTF7_TWING/target.mk b/src/main/target/IFLIGHTF7_TWING/target.mk index 9aef8a877ce..57bc66e9e85 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.mk +++ b/src/main/target/IFLIGHTF7_TWING/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += ONBOARDFLASH VCP +FEATURES += ONBOARDFLASH VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index f6b616e0620..0b65e77e189 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -130,7 +130,6 @@ #define SDCARD_CS_PIN SPI1_NSS_PIN #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PD8 -#define USE_USB_MSC #endif #define USE_I2C diff --git a/src/main/target/MAMBAF405US/target.mk b/src/main/target/MAMBAF405US/target.mk index 43eadf6d0ca..9600e1937b8 100644 --- a/src/main/target/MAMBAF405US/target.mk +++ b/src/main/target/MAMBAF405US/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index 79024c149c7..df11ef86f74 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -72,8 +72,6 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USE_USB_MSC - // *************** M25P256 flash ******************** #define USE_FLASHFS #define USE_FLASH_M25P16 diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 9d0a8727724..9c9cd393a0a 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -107,8 +107,6 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USE_USB_MSC - // *************** UART ***************************** #define USE_VCP #define VBUS_SENSING_PIN PC13 diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index bee9c0b9364..2a9bcbe83dc 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -175,3 +175,7 @@ #define TARGET_IO_PORTD (BIT(2)) #define MAX_PWM_OUTPUT_PORTS 7 + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 3a6ec05412c..9a0a3c5ef1c 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -162,3 +162,7 @@ #define TARGET_IO_PORTD (BIT(2)) #define MAX_PWM_OUTPUT_PORTS 6 + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index ecd74c47e9c..51ef9cdf90c 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -88,8 +88,6 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USE_USB_MSC - // *************** OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index b2a1198c74e..9c0be7255b0 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -21,7 +21,7 @@ #define TARGET_BOARD_IDENTIFIER "MF7P" #define USBD_PRODUCT_STRING "MATEKF722PX" -#define LED0 PA14 //Blue SWCLK +#define LED0 PA14 //Blue SWCLK #define LED1 PA13 //Green SWDIO #define BEEPER PC13 @@ -93,8 +93,6 @@ #define SDCARD_SPI_BUS BUS_SPI2 #define SDCARD_CS_PIN PC15 -#define USE_USB_MSC - // *************** UART ***************************** #define USE_VCP #define USB_DETECT_PIN PC14 @@ -123,7 +121,7 @@ #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 - + #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_TX_PIN PA2 //TX2 pad #define SOFTSERIAL_1_RX_PIN PA2 diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 3d389463b8b..28169a3ab1c 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -123,7 +123,6 @@ # define SDCARD_SPI_BUS BUS_SPI3 # define SDCARD_CS_PIN PD2 # define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -# define USE_USB_MSC #endif // *************** UART ***************************** @@ -150,7 +149,7 @@ #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 - + #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_TX_PIN PA2 #define SOFTSERIAL_1_RX_PIN PA2 @@ -199,4 +198,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT #define USE_SERIALSHOT -#define USE_ESC_SENSOR +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index 0b4c8ce4bd7..5329c419ae3 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -168,7 +168,6 @@ #define SDCARD_SDIO_DMA DMA_TAG(2,3,4) #define SDCARD_SDIO_4BIT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USE_USB_MSC // *************** ADC ***************************** #define USE_ADC diff --git a/src/main/target/NOX/target.mk b/src/main/target/NOX/target.mk index d0c27801a35..913dfd86a72 100755 --- a/src/main/target/NOX/target.mk +++ b/src/main/target/NOX/target.mk @@ -1,5 +1,5 @@ F411_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ @@ -7,4 +7,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/flash_m25p16.c \ drivers/max7456.c - diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 4c619d29505..101d2d98ea3 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -240,7 +240,6 @@ #define M25P16_SPI_BUS BUS_SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16 - #define USE_USB_MSC #endif #define USE_ADC diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index a160dbe0c8e..c3a72620783 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -148,7 +148,6 @@ #define SDCARD_DETECT_PIN PE3 #define SDCARD_SPI_BUS BUS_SPI4 #define SDCARD_CS_PIN SPI4_NSS_PIN -#define USE_USB_MSC #define USE_I2C #define USE_I2C_DEVICE_2 @@ -210,4 +209,4 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff -#define PCA9685_I2C_BUS BUS_I2C2 +#define PCA9685_I2C_BUS BUS_I2C2 \ No newline at end of file diff --git a/src/main/target/OMNIBUSF7NXT/target.mk b/src/main/target/OMNIBUSF7NXT/target.mk index ff0b3579f3d..9be9afc5faf 100644 --- a/src/main/target/OMNIBUSF7NXT/target.mk +++ b/src/main/target/OMNIBUSF7NXT/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/SPEEDYBEEF4/target.mk b/src/main/target/SPEEDYBEEF4/target.mk index 62ba0215c8d..481f0495d8e 100644 --- a/src/main/target/SPEEDYBEEF4/target.mk +++ b/src/main/target/SPEEDYBEEF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h index 86faeea4338..f114662c408 100644 --- a/src/main/target/SPRACINGF7DUAL/target.h +++ b/src/main/target/SPRACINGF7DUAL/target.h @@ -155,8 +155,6 @@ #define SDCARD_SPI_BUS BUS_SPI3 #define SDCARD_CS_PIN PC3 -#define USE_USB_MSC - // disabled for motor outputs 5-8: //#define USE_VTX_RTC6705 //#define USE_VTX_RTC6705_SOFTSPI diff --git a/src/main/target/common.h b/src/main/target/common.h index 8f1158ae849..c130c090917 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -44,6 +44,10 @@ #define SKIP_CLI_RESOURCES #endif +#if defined(STM32F4) || defined(STM32F7) +#define USE_USB_MSC +#endif + #define USE_ADC_AVERAGING #define USE_64BIT_TIME #define USE_BLACKBOX From 192d826ca7a6684f3348745a5f7c385a809d628b Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 12:34:47 +0000 Subject: [PATCH 062/110] set MSC media name "INAV FC" --- src/main/msc/emfat_file.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index 5f7bf951550..e036859598d 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -388,5 +388,5 @@ void emfat_init_files(void) // Detect and list individual power cycle sessions emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1)); - emfat_init(&emfat, "emfat", entries); + emfat_init(&emfat, "INAV FC", entries); } From 29cebf7159acdb967924426889b5ca2fdfd26d9f Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 12:45:31 +0000 Subject: [PATCH 063/110] Revert "set MSC media name "INAV FC"" This reverts commit 192d826ca7a6684f3348745a5f7c385a809d628b. --- src/main/msc/emfat_file.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index e036859598d..5f7bf951550 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -388,5 +388,5 @@ void emfat_init_files(void) // Detect and list individual power cycle sessions emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1)); - emfat_init(&emfat, "INAV FC", entries); + emfat_init(&emfat, "emfat", entries); } From 7ecd99c08680bb44ebda12ec7a76c068bc1362c9 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 13:46:56 +0000 Subject: [PATCH 064/110] set MSC media name "INAV_FC" for internal flash --- src/main/msc/emfat_file.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index 5f7bf951550..c37f542bdc9 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -388,5 +388,5 @@ void emfat_init_files(void) // Detect and list individual power cycle sessions emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1)); - emfat_init(&emfat, "emfat", entries); + emfat_init(&emfat, "INAV_FC", entries); } From 8174b8b7832019b604748fd2bb7d70f28aad348d Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 21:59:10 +0000 Subject: [PATCH 065/110] enable MSC mode for internal flash --- src/main/fc/fc_init.c | 14 ++ src/main/msc/emfat_file.c | 211 +++++++++++++++++++++++++----- src/main/msc/usbd_storage_emfat.c | 12 -- 3 files changed, 189 insertions(+), 48 deletions(-) diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index adf543e207f..e2066da47e2 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -78,6 +78,7 @@ #include "drivers/vtx_common.h" #ifdef USE_USB_MSC #include "drivers/usb_msc.h" +#include "msc/emfat_file.h" #endif #include "drivers/sdcard/sdcard.h" @@ -370,6 +371,19 @@ void init(void) * so there is no bottleneck in reading and writing data */ mscInit(); +#if defined(USE_FLASHFS) + // If the blackbox device is onboard flash, then initialize and scan + // it to identify the log files *before* starting the USB device to + // prevent timeouts of the mass storage device. + if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) { +#ifdef USE_FLASH_M25P16 + // Must initialise the device to read _anything_ + m25p16_init(0); +#endif + emfat_init_files(); + } +#endif + if (mscCheckBoot() || mscCheckButton()) { if (mscStart() == 0) { mscWaitForButton(); diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index c37f542bdc9..3aa0a66ebb7 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -22,17 +22,21 @@ * Author: jflyper@github.com */ +#include "platform.h" #include "common/utils.h" #include "common/printf.h" #include "emfat.h" #include "emfat_file.h" - #include "io/flashfs.h" +#include "common/typeconversion.h" + +#define FILESYSTEM_SIZE_MB 256 +#define HDR_BUF_SIZE 32 #define USE_EMFAT_AUTORUN #define USE_EMFAT_ICON -//#define USE_EMFAT_README +#define USE_EMFAT_README #ifdef USE_EMFAT_AUTORUN static const char autorun_file[] = @@ -47,7 +51,10 @@ static const char autorun_file[] = #ifdef USE_EMFAT_README static const char readme_file[] = - "This is readme file\r\n"; + "inav_all.bbl: All log files concatenated\r\n" + "inav_NNN.bbl: Individual log file\r\n\r\n" + "Note that this file system is read-only\r\n"; + #define README_SIZE (sizeof(readme_file) - 1) #define EMFAT_INCR_README 1 #else @@ -271,7 +278,7 @@ static const unsigned char icon_file[] = #define EMFAT_INCR_ICON 0 #endif -#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1,1,2018, 13,0,0) +#define CMA_TIME EMFAT_ENCODE_CMA_TIME(25,12,2019, 13,0,0) #define CMA { CMA_TIME, CMA_TIME, CMA_TIME } static void memory_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry) @@ -311,82 +318,214 @@ static const emfat_entry_t entriesPredefined[] = #ifdef USE_EMFAT_README { "readme.txt", false, 0, 1, 0, README_SIZE, 1024*1024, (long)readme_file, CMA, memory_read_proc, NULL, { 0 } }, #endif - { "INAV_LOG.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } }, + { "INAV_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } }, + { ".PADDING.TXT", 0, ATTR_HIDDEN, 1, 0, 0, 0, 0, CMA, NULL, NULL, { 0 } }, }; -#define ENTRY_INDEX_BBL (1 + EMFAT_INCR_AUTORUN + EMFAT_INCR_ICON + EMFAT_INCR_README) +#define PREDEFINED_ENTRY_COUNT (1 + EMFAT_INCR_AUTORUN + EMFAT_INCR_ICON + EMFAT_INCR_README) +#define APPENDED_ENTRY_COUNT 2 #define EMFAT_MAX_LOG_ENTRY 100 -#define EMFAT_MAX_ENTRY (ENTRY_INDEX_BBL + EMFAT_MAX_LOG_ENTRY) +#define EMFAT_MAX_ENTRY (PREDEFINED_ENTRY_COUNT + EMFAT_MAX_LOG_ENTRY + APPENDED_ENTRY_COUNT) static emfat_entry_t entries[EMFAT_MAX_ENTRY]; -static char logNames[EMFAT_MAX_LOG_ENTRY][8+3]; emfat_t emfat; +static uint32_t cmaTime = CMA_TIME; + +static void emfat_set_entry_cma(emfat_entry_t *entry) +{ + // Set file creation/modification/access times to be the same, either the default date or that from the RTC + // In practise this will be when the filesystem is mounted as the date is passed from the host over USB + entry->cma_time[0] = cmaTime; + entry->cma_time[1] = cmaTime; + entry->cma_time[2] = cmaTime; +} +#ifdef USE_FLASHFS static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uint32_t size) { - tfp_sprintf(logNames[number], "INAV_%03d.BBL", number); + static char logNames[EMFAT_MAX_LOG_ENTRY][8+1+3]; + + tfp_sprintf(logNames[number], "INAV_%03d.BBL", number + 1); entry->name = logNames[number]; entry->level = 1; entry->offset = offset; entry->curr_size = size; entry->max_size = entry->curr_size; - entry->cma_time[0] = CMA_TIME; - entry->cma_time[1] = CMA_TIME; - entry->cma_time[2] = CMA_TIME; entry->readcb = bblog_read_proc; + // Set file modification/access times to be the same as the creation time + entry->cma_time[1] = entry->cma_time[0]; + entry->cma_time[2] = entry->cma_time[0]; } -static void emfat_find_log(emfat_entry_t *entry, int maxCount) +static int emfat_find_log(emfat_entry_t *entry, int maxCount, int flashfsUsedSpace) { - uint32_t limit = flashfsIdentifyStartOfFreeSpace(); - uint32_t lastOffset = 0; - uint32_t currOffset = 0; + int lastOffset = 0; + int currOffset = 0; + int buffOffset; + int hdrOffset; int fileNumber = 0; - uint8_t buffer[18]; + uint8_t buffer[HDR_BUF_SIZE]; + int logCount = 0; + char *logHeader = "H Product:Blackbox"; + int lenLogHeader = strlen(logHeader); + char *timeHeader = "H Log start datetime:"; + int lenTimeHeader = strlen(timeHeader); + int timeHeaderMatched = 0; - for ( ; currOffset < limit ; currOffset += 2048) { // XXX 2048 = FREE_BLOCK_SIZE in io/flashfs.c + for ( ; currOffset < flashfsUsedSpace ; currOffset += 2048) { // XXX 2048 = FREE_BLOCK_SIZE in io/flashfs.c - flashfsReadAbs(currOffset, buffer, 18); + flashfsReadAbs(currOffset, buffer, HDR_BUF_SIZE); - if (strncmp((char *)buffer, "H Product:Blackbox", 18)) { + if (strncmp((char *)buffer, logHeader, lenLogHeader)) { continue; } + // The length of the previous record is now known if (lastOffset != currOffset) { - emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset); + // Record the previous entry + emfat_add_log(entry++, fileNumber++, lastOffset, currOffset - lastOffset); + + logCount++; + } + + // Find the "Log start datetime" entry, example encoding "H Log start datetime:2019-08-15T13:18:22.199+00:00" + + buffOffset = lenLogHeader; + hdrOffset = currOffset; + + // Set the default timestamp for this log entry in case the timestamp is not found + entry->cma_time[0] = cmaTime; + + // Search for the timestamp record + while (true) { + if (buffer[buffOffset++] == timeHeader[timeHeaderMatched]) { + // This matches the header we're looking for so far + if (++timeHeaderMatched == lenTimeHeader) { + // Complete match so read date/time into buffer + flashfsReadAbs(hdrOffset + buffOffset, buffer, HDR_BUF_SIZE); + + // Extract the time values to create the CMA time + + char *last; + char* tok = strtok_r((char *)buffer, "-T:.", &last); + int index=0; + int year=0,month,day,hour,min,sec; + while (tok != NULL) { + switch(index) { + case 0: + year = fastA2I(tok); + break; + case 1: + month = fastA2I(tok); + break; + case 2: + day = fastA2I(tok); + break; + case 3: + hour = fastA2I(tok); + break; + case 4: + min = fastA2I(tok); + break; + case 5: + sec = fastA2I(tok); + break; + } + if(index == 5) + break; + index++; + tok = strtok_r(NULL, "-T:.", &last); + } + // Set the file creation time + if (year) { + entry->cma_time[0] = EMFAT_ENCODE_CMA_TIME(day, month, year, hour, min, sec); + } + break; + } + } else { + timeHeaderMatched = 0; + } - ++fileNumber; - if (fileNumber == maxCount) { - break; + if (buffOffset == HDR_BUF_SIZE) { + // Read the next portion of the header + hdrOffset += HDR_BUF_SIZE; + + // Check for flash overflow + if (hdrOffset > flashfsUsedSpace) { + break; + } + flashfsReadAbs(hdrOffset, buffer, HDR_BUF_SIZE); + buffOffset = 0; } - ++entry; + } + + if (fileNumber == maxCount) { + break; } lastOffset = currOffset; } + // Now add the final entry if (fileNumber != maxCount && lastOffset != currOffset) { emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset); + ++logCount; } + + return logCount; } +#else +#warning "Undefined USE_FLASHFS" +#endif // USE_FLASHFS void emfat_init_files(void) { - memset(entries, 0, sizeof(entries)); - - for (size_t i = 0 ; i < ARRAYLEN(entriesPredefined) ; i++) { + int flashfsUsedSpace = 0; + int entryIndex = PREDEFINED_ENTRY_COUNT; + emfat_entry_t *entry; + +#ifdef USE_FLASHFS + flashfsInit(); + flashfsUsedSpace = flashfsIdentifyStartOfFreeSpace(); + + // Detect and create entries for each individual log + const int logCount = emfat_find_log(&entries[PREDEFINED_ENTRY_COUNT], EMFAT_MAX_LOG_ENTRY, flashfsUsedSpace); + + entryIndex += logCount; + + if (logCount > 0) { + // Use the first log time for predefined entries + cmaTime = entries[PREDEFINED_ENTRY_COUNT].cma_time[0]; + // Create the all logs entry that represents all used flash space to + // allow downloading the entire log in one file + entries[entryIndex] = entriesPredefined[PREDEFINED_ENTRY_COUNT]; + entry = &entries[entryIndex]; + entry->curr_size = flashfsUsedSpace; + entry->max_size = entry->curr_size; + // This entry has timestamps corresponding to when the filesystem is mounted + emfat_set_entry_cma(entry); + ++entryIndex; + } +#else +#warning "Undefined USE_FLASHFS" +#endif // USE_FLASHFS + + // Padding file to fill out the filesystem size to FILESYSTEM_SIZE_MB + if (flashfsUsedSpace * 2 < FILESYSTEM_SIZE_MB * 1024 * 1024) { + entries[entryIndex] = entriesPredefined[PREDEFINED_ENTRY_COUNT + 1]; + entry = &entries[entryIndex]; + // used space is doubled because of the individual files plus the single complete file + entry->curr_size = (FILESYSTEM_SIZE_MB * 1024 * 1024) - (flashfsUsedSpace * 2); + entry->max_size = entry->curr_size; + emfat_set_entry_cma(entry); + } + // create the predefined entries + for (size_t i = 0 ; i < PREDEFINED_ENTRY_COUNT ; i++) { entries[i] = entriesPredefined[i]; + emfat_set_entry_cma(&entries[i]); } - // Singleton - emfat_entry_t *entry = &entries[ENTRY_INDEX_BBL]; - entry->curr_size = flashfsIdentifyStartOfFreeSpace(); - entry->max_size = flashfsGetSize(); - - // Detect and list individual power cycle sessions - emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1)); - emfat_init(&emfat, "INAV_FC", entries); } diff --git a/src/main/msc/usbd_storage_emfat.c b/src/main/msc/usbd_storage_emfat.c index 2257a404db2..070df79f830 100644 --- a/src/main/msc/usbd_storage_emfat.c +++ b/src/main/msc/usbd_storage_emfat.c @@ -64,18 +64,6 @@ static int8_t STORAGE_Init(uint8_t lun) { UNUSED(lun); - LED0_ON; - -#ifdef USE_FLASHFS -#ifdef USE_FLASH - flashInit(flashConfig()); -#endif - flashfsInit(); -#endif - emfat_init_files(); - - delay(1000); - LED0_OFF; return 0; From f7df26ef629add7b0417afde15a04f89ea96870f Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 20 Dec 2019 22:34:26 +0000 Subject: [PATCH 066/110] update documentation for internal flash usage --- docs/USB_Mass_Storage_(MSC)_mode.md | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index f81047ad685..8184a0e8ede 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -2,6 +2,13 @@ iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card access, meaning you can mount the FC (SD card) as an OS file system via USB to read BB logs (and delete them). +MSC mode can also be used with internal flash blackbox logging. In this case: + +* The file system is read-only. In order to delete logs it is necessary to clear the flash (configurator, CLI or other tool). +* The logs are presented as a single, consolidated file (`inav_all.bbl`) and individual logs (`inav_001.bbl` etc.). +* Other informative files (e.g. `readme.txt`) may also exist in the virtual file system. + + ## Usage To put the FC in MSC mode: @@ -16,7 +23,9 @@ To put the FC in MSC mode: ## Performance -Reading is quite slow, typically c. 340kBs, for example: +Internal flash is quite fast. + +For an SD card, reading is quite slow, typically c. 340kBs, for example: ``` #################### From 7925168cd3b6ef3780acae45375b9f4f45206f61 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 21 Dec 2019 13:43:12 +0000 Subject: [PATCH 067/110] tidy up and extend USE_FLASHFS exclusions in emfat_file --- src/main/msc/emfat_file.c | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index 3aa0a66ebb7..5d3c0d81422 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -476,17 +476,15 @@ static int emfat_find_log(emfat_entry_t *entry, int maxCount, int flashfsUsedSpa return logCount; } -#else -#warning "Undefined USE_FLASHFS" #endif // USE_FLASHFS void emfat_init_files(void) { +#ifdef USE_FLASHFS int flashfsUsedSpace = 0; int entryIndex = PREDEFINED_ENTRY_COUNT; emfat_entry_t *entry; -#ifdef USE_FLASHFS flashfsInit(); flashfsUsedSpace = flashfsIdentifyStartOfFreeSpace(); @@ -508,9 +506,6 @@ void emfat_init_files(void) emfat_set_entry_cma(entry); ++entryIndex; } -#else -#warning "Undefined USE_FLASHFS" -#endif // USE_FLASHFS // Padding file to fill out the filesystem size to FILESYSTEM_SIZE_MB if (flashfsUsedSpace * 2 < FILESYSTEM_SIZE_MB * 1024 * 1024) { @@ -521,11 +516,11 @@ void emfat_init_files(void) entry->max_size = entry->curr_size; emfat_set_entry_cma(entry); } +#endif // USE_FLASHFS // create the predefined entries for (size_t i = 0 ; i < PREDEFINED_ENTRY_COUNT ; i++) { entries[i] = entriesPredefined[i]; emfat_set_entry_cma(&entries[i]); } - emfat_init(&emfat, "INAV_FC", entries); } From b5106081a22761c5fd75ade75a2ba2fcaa4b29ff Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 21 Dec 2019 13:57:48 +0000 Subject: [PATCH 068/110] update USB MSC documentation --- docs/USB_Mass_Storage_(MSC)_mode.md | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index 8184a0e8ede..4132cfa3b2e 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -1,8 +1,8 @@ ## Overview -iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card access, meaning you can mount the FC (SD card) as an OS file system via USB to read BB logs (and delete them). +iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card). -MSC mode can also be used with internal flash blackbox logging. In this case: +When MSC mode is used with internal flash blackbox logging: * The file system is read-only. In order to delete logs it is necessary to clear the flash (configurator, CLI or other tool). * The logs are presented as a single, consolidated file (`inav_all.bbl`) and individual logs (`inav_001.bbl` etc.). @@ -81,3 +81,13 @@ Data rate 496Hz 35806 bytes/s 358100 baud 3 frames failed to decode, rendering 4 loop iterations unreadable. 4 iterations are missing in total (4ms, 0.00%) 774472 loop iterations weren't logged because of your blackbox_rate settings (779980ms, 50.00%) ``` +## Developer Notes + +Providing MSC for a target requires that the `.mk` file includes in `FEATURES` the key `MSC` and at least one of `ONBOARDFLASH` and /or `SDCARD`. + +For F4 and F7 targets, `USE_USB_MSC` is set unconditionally in `common.h`; if your target does not support blackbox logging to either SD card or internal flash, you should over-ride this in `target.h` +``` +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif +``` \ No newline at end of file From c57c8d18d743d124dfb94bcc6841168fee147414 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 21 Dec 2019 16:51:00 +0000 Subject: [PATCH 069/110] update target files for remaining targets --- src/main/target/AIKONF4/target.mk | 2 +- src/main/target/ASGARD32F4/target.mk | 2 +- src/main/target/DALRCF722DUAL/target.mk | 2 +- src/main/target/FF_PIKOF4/target.mk | 3 +-- src/main/target/FIREWORKSV2/target.mk | 2 +- src/main/target/FISHDRONEF4/target.mk | 2 +- src/main/target/FOXEERF405/target.mk | 2 +- src/main/target/FOXEERF722DUAL/target.mk | 2 +- src/main/target/IFLIGHTF4_TWING/target.mk | 4 ++-- src/main/target/KAKUTEF4/target.mk | 2 +- src/main/target/MAMBAF722/target.mk | 2 +- src/main/target/PIXRACER/target.h | 4 ++++ src/main/target/REVO/target.mk | 2 +- src/main/target/SPARKY2/target.mk | 2 +- src/main/target/YUPIF7/target.mk | 2 +- 15 files changed, 19 insertions(+), 16 deletions(-) diff --git a/src/main/target/AIKONF4/target.mk b/src/main/target/AIKONF4/target.mk index 4bc8ef110a9..a8604c383d1 100644 --- a/src/main/target/AIKONF4/target.mk +++ b/src/main/target/AIKONF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH +FEATURES = VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/ASGARD32F4/target.mk b/src/main/target/ASGARD32F4/target.mk index 62ba0215c8d..481f0495d8e 100644 --- a/src/main/target/ASGARD32F4/target.mk +++ b/src/main/target/ASGARD32F4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/DALRCF722DUAL/target.mk b/src/main/target/DALRCF722DUAL/target.mk index d1602929817..565e12230b3 100644 --- a/src/main/target/DALRCF722DUAL/target.mk +++ b/src/main/target/DALRCF722DUAL/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ diff --git a/src/main/target/FF_PIKOF4/target.mk b/src/main/target/FF_PIKOF4/target.mk index 234c6ad4458..b268ca55885 100644 --- a/src/main/target/FF_PIKOF4/target.mk +++ b/src/main/target/FF_PIKOF4/target.mk @@ -1,9 +1,8 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ drivers/max7456.c \ drivers/light_ws2811strip.c - \ No newline at end of file diff --git a/src/main/target/FIREWORKSV2/target.mk b/src/main/target/FIREWORKSV2/target.mk index b7423b68ca7..7d8a5945de4 100644 --- a/src/main/target/FIREWORKSV2/target.mk +++ b/src/main/target/FIREWORKSV2/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/FISHDRONEF4/target.mk b/src/main/target/FISHDRONEF4/target.mk index ab900e2a149..5583e8d0b93 100644 --- a/src/main/target/FISHDRONEF4/target.mk +++ b/src/main/target/FISHDRONEF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH +FEATURES += SDCARD VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/FOXEERF405/target.mk b/src/main/target/FOXEERF405/target.mk index 23c3774fdfe..86025b89c11 100644 --- a/src/main/target/FOXEERF405/target.mk +++ b/src/main/target/FOXEERF405/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/FOXEERF722DUAL/target.mk b/src/main/target/FOXEERF722DUAL/target.mk index ea8a3a9209f..30faa4e33cf 100644 --- a/src/main/target/FOXEERF722DUAL/target.mk +++ b/src/main/target/FOXEERF722DUAL/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/IFLIGHTF4_TWING/target.mk b/src/main/target/IFLIGHTF4_TWING/target.mk index dbbd64e7ad9..89793194927 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.mk +++ b/src/main/target/IFLIGHTF4_TWING/target.mk @@ -1,6 +1,6 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ @@ -12,4 +12,4 @@ TARGET_SRC = \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ drivers/light_ws2811strip.c \ - drivers/max7456.c \ No newline at end of file + drivers/max7456.c diff --git a/src/main/target/KAKUTEF4/target.mk b/src/main/target/KAKUTEF4/target.mk index 74fab0fb57f..37de6e063eb 100755 --- a/src/main/target/KAKUTEF4/target.mk +++ b/src/main/target/KAKUTEF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ diff --git a/src/main/target/MAMBAF722/target.mk b/src/main/target/MAMBAF722/target.mk index 1902b593105..5a3023d0843 100644 --- a/src/main/target/MAMBAF722/target.mk +++ b/src/main/target/MAMBAF722/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ diff --git a/src/main/target/PIXRACER/target.h b/src/main/target/PIXRACER/target.h index a695ebcc855..c12cd044a2e 100755 --- a/src/main/target/PIXRACER/target.h +++ b/src/main/target/PIXRACER/target.h @@ -175,3 +175,7 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff + +#ifdef USE_USB_MSC +# undef USE_USB_MSC +#endif diff --git a/src/main/target/REVO/target.mk b/src/main/target/REVO/target.mk index b30794eff9a..ff9b702cdb5 100644 --- a/src/main/target/REVO/target.mk +++ b/src/main/target/REVO/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ diff --git a/src/main/target/SPARKY2/target.mk b/src/main/target/SPARKY2/target.mk index 1487b00b103..64c49354947 100644 --- a/src/main/target/SPARKY2/target.mk +++ b/src/main/target/SPARKY2/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ diff --git a/src/main/target/YUPIF7/target.mk b/src/main/target/YUPIF7/target.mk index 1ad0bac85eb..7c4c979b9bb 100644 --- a/src/main/target/YUPIF7/target.mk +++ b/src/main/target/YUPIF7/target.mk @@ -1,5 +1,5 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH +FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu6050.c \ From 02cf4467f3c718889a15667939bee7860f251dcf Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 21 Dec 2019 16:52:49 +0000 Subject: [PATCH 070/110] update target files for remaining targets --- src/main/target/PIXRACER/target.h | 4 ---- src/main/target/PIXRACER/target.mk | 2 +- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/src/main/target/PIXRACER/target.h b/src/main/target/PIXRACER/target.h index c12cd044a2e..a695ebcc855 100755 --- a/src/main/target/PIXRACER/target.h +++ b/src/main/target/PIXRACER/target.h @@ -175,7 +175,3 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/PIXRACER/target.mk b/src/main/target/PIXRACER/target.mk index 258785f2f3e..4f4343a7bfa 100755 --- a/src/main/target/PIXRACER/target.mk +++ b/src/main/target/PIXRACER/target.mk @@ -1,5 +1,5 @@ F427_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP MSC HSE_VALUE = 24000000 From b94d2cd24e9326681ca0d46b764ccf235f24bf23 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 21 Dec 2019 17:19:33 +0000 Subject: [PATCH 071/110] clarify documentation concerning internal flash usage --- docs/USB_Mass_Storage_(MSC)_mode.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index 4132cfa3b2e..730230db12a 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -2,10 +2,10 @@ iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card). -When MSC mode is used with internal flash blackbox logging: +When MSC mode is used with **internal flash** there are a few differences compared to **SD card** as it's a virtual file system: -* The file system is read-only. In order to delete logs it is necessary to clear the flash (configurator, CLI or other tool). -* The logs are presented as a single, consolidated file (`inav_all.bbl`) and individual logs (`inav_001.bbl` etc.). +* The file system is read-only. In order to delete logs it is necessary to erase the flash as usual (configurator, CLI or other tool). +* The logs are presented as a single, consolidated file (`inav_all.bbl`) as well as individual logs (`inav_001.bbl` etc.). * Other informative files (e.g. `readme.txt`) may also exist in the virtual file system. From f7f26fe0e3219e6edf2223f912236c4fa7ebd2f7 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sat, 21 Dec 2019 20:51:16 +0100 Subject: [PATCH 072/110] Fix rssi_source = auto --- src/main/rx/rx.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 6cf228eb802..7ba4884c9c5 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -364,7 +364,7 @@ void rxUpdateRSSISource(void) } } - if (rxConfig()->rssi_source == RSSI_SOURCE_RX_PROTOCOL) { + if (rxConfig()->rssi_source == RSSI_SOURCE_RX_PROTOCOL || rxConfig()->rssi_source == RSSI_SOURCE_AUTO) { activeRssiSource = RSSI_SOURCE_RX_PROTOCOL; return; } @@ -736,4 +736,4 @@ uint16_t lqTrackerGet(rxLinkQualityTracker_e * lqTracker) } return lqTracker->lqValue; -} \ No newline at end of file +} From fb085493e7b2b20984ac530f95cd1de03dcdfefe Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 22 Dec 2019 17:11:26 +0100 Subject: [PATCH 073/110] Lower default PID sum Yaw limit --- src/main/flight/pid.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 23aeb3dc584..2ff0e922f4f 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -24,7 +24,7 @@ #define PID_SUM_LIMIT_MIN 100 #define PID_SUM_LIMIT_MAX 1000 #define PID_SUM_LIMIT_DEFAULT 500 -#define PID_SUM_LIMIT_YAW_DEFAULT 400 +#define PID_SUM_LIMIT_YAW_DEFAULT 350 #define HEADING_HOLD_RATE_LIMIT_MIN 10 #define HEADING_HOLD_RATE_LIMIT_MAX 250 From 4fd2149e2be739e46484be08ffdcb7ad8f027e4d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 22 Dec 2019 21:33:19 +0100 Subject: [PATCH 074/110] Drop min_throttle in favor of throttle IDLE percent --- src/main/blackbox/blackbox.c | 8 ++-- src/main/cms/cms_menu_misc.c | 2 +- src/main/fc/fc_core.c | 6 +-- src/main/fc/fc_msp.c | 8 ++-- src/main/fc/rc_curves.c | 4 +- src/main/fc/settings.yaml | 8 ++-- src/main/flight/failsafe.c | 4 +- src/main/flight/mixer.c | 39 ++++++++++++-------- src/main/flight/mixer.h | 3 +- src/main/flight/pid.c | 8 ++-- src/main/flight/rth_estimator.c | 2 +- src/main/navigation/navigation_fixedwing.c | 4 +- src/main/navigation/navigation_fw_launch.c | 8 ++-- src/main/navigation/navigation_multicopter.c | 14 +++---- src/main/target/ALIENFLIGHTF3/config.c | 1 - src/main/target/ALIENFLIGHTF4/config.c | 1 - src/main/target/ALIENFLIGHTNGF7/config.c | 1 - src/main/target/ASGARD32F4/config.c | 1 - src/main/target/ASGARD32F7/config.c | 1 - src/main/target/FALCORE/config.c | 1 - 20 files changed, 63 insertions(+), 61 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 7d5aaee7985..c0e6b58c2f7 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -755,7 +755,7 @@ static void writeIntraframe(void) * Write the throttle separately from the rest of the RC data so we can apply a predictor to it. * Throttle lies in range [minthrottle..maxthrottle]: */ - blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - motorConfig()->minthrottle); + blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - getThrottleIdleValue()); if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { /* @@ -809,7 +809,7 @@ static void writeIntraframe(void) } //Motors can be below minthrottle when disarmed, but that doesn't happen much - blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - motorConfig()->minthrottle); + blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - getThrottleIdleValue()); //Motors tend to be similar to each other so use the first motor's value as a predictor of the others const int motorCount = getMotorCount(); @@ -1618,10 +1618,10 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("Log start datetime", "%s", blackboxGetStartDateTime(buf)); BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", systemConfig()->name); BLACKBOX_PRINT_HEADER_LINE("P interval", "%u/%u", blackboxConfig()->rate_num, blackboxConfig()->rate_denom); - BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle); + BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", getThrottleIdleValue()); BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle); BLACKBOX_PRINT_HEADER_LINE("gyro_scale", "0x%x", castFloatBytesToInt(1.0f)); - BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", motorConfig()->minthrottle,motorConfig()->maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle); BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G); BLACKBOX_PRINT_HEADER_LINE_CUSTOM( diff --git a/src/main/cms/cms_menu_misc.c b/src/main/cms/cms_menu_misc.c index 2a3a7610d71..15916826fa0 100644 --- a/src/main/cms/cms_menu_misc.c +++ b/src/main/cms/cms_menu_misc.c @@ -42,7 +42,7 @@ static const OSD_Entry menuMiscEntries[]= { OSD_LABEL_ENTRY("-- MISC --"), - OSD_SETTING_ENTRY("MIN THR", SETTING_MIN_THROTTLE), + OSD_SETTING_ENTRY("THR IDLE", SETTING_THROTTLE_IDLE), #if defined(USE_OSD) && defined(USE_ADC) OSD_SETTING_ENTRY("OSD VOLT DECIMALS", SETTING_OSD_MAIN_VOLTAGE_DECIMALS), OSD_SETTING_ENTRY("STATS ENERGY UNIT", SETTING_OSD_STATS_ENERGY_UNIT), diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 497e153be6e..5d417f702b9 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -793,9 +793,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs) } if (thrTiltCompStrength) { - rcCommand[THROTTLE] = constrain(motorConfig()->minthrottle - + (rcCommand[THROTTLE] - motorConfig()->minthrottle) * calculateThrottleTiltCompensationFactor(thrTiltCompStrength), - motorConfig()->minthrottle, + rcCommand[THROTTLE] = constrain(getThrottleIdleValue() + + (rcCommand[THROTTLE] - getThrottleIdleValue()) * calculateThrottleTiltCompensationFactor(thrTiltCompStrength), + getThrottleIdleValue(), motorConfig()->maxthrottle); } } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ccc95861368..75db8a94b17 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -702,7 +702,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP_MISC: sbufWriteU16(dst, PWM_RANGE_MIDDLE); - sbufWriteU16(dst, motorConfig()->minthrottle); + sbufWriteU16(dst, 0); // Was min_throttle sbufWriteU16(dst, motorConfig()->maxthrottle); sbufWriteU16(dst, motorConfig()->mincommand); @@ -732,7 +732,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP2_INAV_MISC: sbufWriteU16(dst, PWM_RANGE_MIDDLE); - sbufWriteU16(dst, motorConfig()->minthrottle); + sbufWriteU16(dst, 0); //Was min_throttle sbufWriteU16(dst, motorConfig()->maxthrottle); sbufWriteU16(dst, motorConfig()->mincommand); @@ -1712,7 +1712,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (dataSize >= 22) { sbufReadU16(src); // midrc - motorConfigMutable()->minthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); //Was min_throttle motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); @@ -1753,7 +1753,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (dataSize == 41) { sbufReadU16(src); // midrc - motorConfigMutable()->minthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); // was min_throttle motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c index b9ff0b8fb5a..ff0ce991f9c 100644 --- a/src/main/fc/rc_curves.c +++ b/src/main/fc/rc_curves.c @@ -41,7 +41,7 @@ int16_t lookupThrottleRCMid; // THROTTLE curve mid point void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) { - lookupThrottleRCMid = motorConfig()->minthrottle + (int32_t)(motorConfig()->maxthrottle - motorConfig()->minthrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRCMid = getThrottleIdleValue() + (int32_t)(motorConfig()->maxthrottle - getThrottleIdleValue()) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { const int16_t tmp = 10 * i - controlRateConfig->throttle.rcMid8; @@ -51,7 +51,7 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) if (tmp < 0) y = controlRateConfig->throttle.rcMid8; lookupThrottleRC[i] = 10 * controlRateConfig->throttle.rcMid8 + tmp * (100 - controlRateConfig->throttle.rcExpo8 + (int32_t) controlRateConfig->throttle.rcExpo8 * (tmp * tmp) / (y * y)) / 10; - lookupThrottleRC[i] = motorConfig()->minthrottle + (int32_t) (motorConfig()->maxthrottle - motorConfig()->minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRC[i] = getThrottleIdleValue() + (int32_t) (motorConfig()->maxthrottle - getThrottleIdleValue()) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } } diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ffc15a559be..ee98c5824e2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -478,10 +478,6 @@ groups: type: motorConfig_t headers: ["flight/mixer.h"] members: - - name: min_throttle - field: minthrottle - min: PWM_RANGE_MIN - max: PWM_RANGE_MAX - name: max_throttle field: maxthrottle min: PWM_RANGE_MIN @@ -509,6 +505,10 @@ groups: field: throttleScale min: 0 max: 1 + - name: throttle_idle + field: throttleIdle + min: 4 + max: 30 - name: motor_poles field: motorPoleCount min: 4 diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 2fcf1251c01..b03da0541ec 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -216,7 +216,7 @@ bool failsafeRequiresMotorStop(void) { return failsafeState.active && failsafeState.activeProcedure == FAILSAFE_PROCEDURE_AUTO_LANDING && - failsafeConfig()->failsafe_throttle < motorConfig()->minthrottle; + failsafeConfig()->failsafe_throttle < getThrottleIdleValue(); } void failsafeStartMonitoring(void) @@ -287,7 +287,7 @@ void failsafeApplyControlInput(void) break; case THROTTLE: - rcCommand[idx] = feature(FEATURE_3D) ? PWM_RANGE_MIDDLE : motorConfig()->minthrottle; + rcCommand[idx] = feature(FEATURE_3D) ? PWM_RANGE_MIDDLE : getThrottleIdleValue(); break; } break; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 60c8e03f069..e8da35a01df 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -61,6 +61,7 @@ static float mixerScale = 1.0f; static EXTENDED_FASTRAM motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static EXTENDED_FASTRAM uint8_t motorCount = 0; EXTENDED_FASTRAM int mixerThrottleCommand; +static EXTENDED_FASTRAM int throttleIdleValue = 1150; PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0); @@ -96,7 +97,6 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 4); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, - .minthrottle = DEFAULT_MIN_THROTTLE, .motorPwmProtocol = DEFAULT_PWM_PROTOCOL, .motorPwmRate = DEFAULT_PWM_RATE, .maxthrottle = DEFAULT_MAX_THROTTLE, @@ -104,6 +104,7 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorAccelTimeMs = 0, .motorDecelTimeMs = 0, .digitalIdleOffsetValue = 450, // Same scale as in Betaflight + .throttleIdle = 15.0f, .throttleScale = 1.0f, .motorPoleCount = 14 // Most brushless motors that we use are 14 poles ); @@ -113,6 +114,11 @@ PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTO typedef void (*motorRateLimitingApplyFnPtr)(const float dT); static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn; +int getThrottleIdleValue(void) +{ + return throttleIdleValue; +} + static void computeMotorCount(void) { motorCount = 0; @@ -174,7 +180,7 @@ void applyMotorRateLimiting(const float dT) } else { // Calculate max motor step - const uint16_t motorRange = motorConfig()->maxthrottle - motorConfig()->minthrottle; + const uint16_t motorRange = motorConfig()->maxthrottle - throttleIdleValue; const float motorMaxInc = (motorConfig()->motorAccelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorAccelTimeMs * 1e-3f); const float motorMaxDec = (motorConfig()->motorDecelTimeMs == 0) ? 2000 : motorRange * dT / (motorConfig()->motorDecelTimeMs * 1e-3f); @@ -183,12 +189,12 @@ void applyMotorRateLimiting(const float dT) motorPrevious[i] = constrainf(motor[i], motorPrevious[i] - motorMaxDec, motorPrevious[i] + motorMaxInc); // Handle throttle below min_throttle (motor start/stop) - if (motorPrevious[i] < motorConfig()->minthrottle) { - if (motor[i] < motorConfig()->minthrottle) { + if (motorPrevious[i] < throttleIdleValue) { + if (motor[i] < throttleIdleValue) { motorPrevious[i] = motor[i]; } else { - motorPrevious[i] = motorConfig()->minthrottle; + motorPrevious[i] = throttleIdleValue; } } } @@ -202,6 +208,7 @@ void applyMotorRateLimiting(const float dT) void mixerInit(void) { + throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * motorConfig()->throttleIdle); computeMotorCount(); loadPrimaryMotorMixer(); // in 3D mode, mixer gain has to be halved @@ -237,8 +244,8 @@ void FAST_CODE NOINLINE writeMotors(void) const float dshotMinThrottleOffset = (DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 10000.0f * motorConfig()->digitalIdleOffsetValue; if (feature(FEATURE_3D)) { - if (motor[i] >= motorConfig()->minthrottle && motor[i] <= flight3DConfig()->deadband3d_low) { - motorValue = scaleRangef(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, dshotMinThrottleOffset + DSHOT_MIN_THROTTLE); + if (motor[i] >= throttleIdleValue && motor[i] <= flight3DConfig()->deadband3d_low) { + motorValue = scaleRangef(motor[i], throttleIdleValue, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, dshotMinThrottleOffset + DSHOT_MIN_THROTTLE); motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_3D_DEADBAND_LOW); } else if (motor[i] >= flight3DConfig()->deadband3d_high && motor[i] <= motorConfig()->maxthrottle) { @@ -250,11 +257,11 @@ void FAST_CODE NOINLINE writeMotors(void) } } else { - if (motor[i] < motorConfig()->minthrottle) { // motor disarmed + if (motor[i] < throttleIdleValue) { // motor disarmed motorValue = DSHOT_DISARM_COMMAND; } else { - motorValue = scaleRangef(motor[i], motorConfig()->minthrottle, motorConfig()->maxthrottle, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE); + motorValue = scaleRangef(motor[i], throttleIdleValue, motorConfig()->maxthrottle, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE); motorValue = constrain(motorValue, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE); } } @@ -337,7 +344,7 @@ void FAST_CODE NOINLINE mixTable(const float dT) // Find min and max throttle based on condition. #ifdef USE_GLOBAL_FUNCTIONS if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) { - throttleMin = motorConfig()->minthrottle; + throttleMin = throttleIdleValue; throttleMax = motorConfig()->maxthrottle; mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleMin, throttleMax); } else @@ -347,7 +354,7 @@ void FAST_CODE NOINLINE mixTable(const float dT) if ((rcCommand[THROTTLE] <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle))) { // Out of band handling throttleMax = flight3DConfig()->deadband3d_low; - throttleMin = motorConfig()->minthrottle; + throttleMin = throttleIdleValue; throttlePrevious = mixerThrottleCommand = rcCommand[THROTTLE]; } else if (rcCommand[THROTTLE] >= (PWM_RANGE_MIDDLE + rcControlsConfig()->deadband3d_throttle)) { // Positive handling throttleMax = motorConfig()->maxthrottle; @@ -355,14 +362,14 @@ void FAST_CODE NOINLINE mixTable(const float dT) throttlePrevious = mixerThrottleCommand = rcCommand[THROTTLE]; } else if ((throttlePrevious <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive mixerThrottleCommand = throttleMax = flight3DConfig()->deadband3d_low; - throttleMin = motorConfig()->minthrottle; + throttleMin = throttleIdleValue; } else { // Deadband handling from positive to negative throttleMax = motorConfig()->maxthrottle; mixerThrottleCommand = throttleMin = flight3DConfig()->deadband3d_high; } } else { mixerThrottleCommand = rcCommand[THROTTLE]; - throttleMin = motorConfig()->minthrottle; + throttleMin = throttleIdleValue; throttleMax = motorConfig()->maxthrottle; // Throttle scaling to limit max throttle when battery is full @@ -404,12 +411,12 @@ void FAST_CODE NOINLINE mixTable(const float dT) motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle); } else if (feature(FEATURE_3D)) { if (throttlePrevious <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle)) { - motor[i] = constrain(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low); + motor[i] = constrain(motor[i], throttleIdleValue, flight3DConfig()->deadband3d_low); } else { motor[i] = constrain(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle); } } else { - motor[i] = constrain(motor[i], motorConfig()->minthrottle, motorConfig()->maxthrottle); + motor[i] = constrain(motor[i], throttleIdleValue, motorConfig()->maxthrottle); } // Motor stop handling @@ -417,7 +424,7 @@ void FAST_CODE NOINLINE mixTable(const float dT) if (feature(FEATURE_MOTOR_STOP)) { motor[i] = (feature(FEATURE_3D) ? PWM_RANGE_MIDDLE : motorConfig()->mincommand); } else { - motor[i] = motorConfig()->minthrottle; + motor[i] = throttleIdleValue; } } } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 13f27dc91d0..9fc9d35b75f 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -83,7 +83,6 @@ PG_DECLARE(flight3DConfig_t, flight3DConfig); typedef struct motorConfig_s { // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms) - uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed. uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) @@ -91,6 +90,7 @@ typedef struct motorConfig_s { uint16_t motorAccelTimeMs; // Time limit for motor to accelerate from 0 to 100% throttle [ms] uint16_t motorDecelTimeMs; // Time limit for motor to decelerate from 0 to 100% throttle [ms] uint16_t digitalIdleOffsetValue; + float throttleIdle; // Throttle IDLE value based on min_command, max_throttle, in percent float throttleScale; // Scaling factor for throttle. uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry } motorConfig_t; @@ -107,6 +107,7 @@ extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; extern int mixerThrottleCommand; +int getThrottleIdleValue(void); uint8_t getMotorCount(void); float getMotorMixRange(void); bool mixerIsOutputSaturated(void); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 9d5d09fa7e8..73ab84b9abc 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -322,7 +322,7 @@ void pidResetTPAFilter(void) { if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) { pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, getLooptime() * 1e-6f); - pt1FilterReset(&fixedWingTpaFilter, motorConfig()->minthrottle); + pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue()); } } @@ -370,10 +370,10 @@ static float calculateFixedWingTPAFactor(uint16_t throttle) // tpa_rate is amount of curve TPA applied to PIDs // tpa_breakpoint for fixed wing is cruise throttle value (value at which PIDs were tuned) - if (currentControlRateProfile->throttle.dynPID != 0 && currentControlRateProfile->throttle.pa_breakpoint > motorConfig()->minthrottle) { - if (throttle > motorConfig()->minthrottle) { + if (currentControlRateProfile->throttle.dynPID != 0 && currentControlRateProfile->throttle.pa_breakpoint > getThrottleIdleValue()) { + if (throttle > getThrottleIdleValue()) { // Calculate TPA according to throttle - tpaFactor = 0.5f + ((float)(currentControlRateProfile->throttle.pa_breakpoint - motorConfig()->minthrottle) / (throttle - motorConfig()->minthrottle) / 2.0f); + tpaFactor = 0.5f + ((float)(currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue()) / (throttle - getThrottleIdleValue()) / 2.0f); // Limit to [0.5; 2] range tpaFactor = constrainf(tpaFactor, 0.5f, 2.0f); diff --git a/src/main/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index fc2e7706fcd..57150007142 100644 --- a/src/main/flight/rth_estimator.c +++ b/src/main/flight/rth_estimator.c @@ -79,7 +79,7 @@ static int8_t RTHInitialAltitudeChangePitchAngle(float altitudeChange) { static float estimatePitchPower(float pitch) { int16_t altitudeChangeThrottle = fixedWingPitchToThrottleCorrection(DEGREES_TO_DECIDEGREES(pitch)); altitudeChangeThrottle = constrain(altitudeChangeThrottle, navConfig()->fw.min_throttle, navConfig()->fw.max_throttle); - const float altitudeChangeThrToCruiseThrRatio = (float)(altitudeChangeThrottle - motorConfig()->minthrottle) / (navConfig()->fw.cruise_throttle - motorConfig()->minthrottle); + const float altitudeChangeThrToCruiseThrRatio = (float)(altitudeChangeThrottle - getThrottleIdleValue()) / (navConfig()->fw.cruise_throttle - getThrottleIdleValue()); return (float)heatLossesCompensatedPower(batteryMetersConfig()->idle_power + batteryMetersConfig()->cruise_power * altitudeChangeThrToCruiseThrRatio) / 100; } diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index ae475fedf18..f7d08917616 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -484,7 +484,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat isAutoThrottleManuallyIncreased = false; } - rcCommand[THROTTLE] = constrain(correctedThrottleValue, motorConfig()->minthrottle, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain(correctedThrottleValue, getThrottleIdleValue(), motorConfig()->maxthrottle); } #ifdef NAV_FIXED_WING_LANDING @@ -497,7 +497,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat ((posControl.flags.estAglStatus == EST_TRUSTED) && (posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) ) { // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled - rcCommand[THROTTLE] = motorConfig()->minthrottle; + rcCommand[THROTTLE] = getThrottleIdleValue(); ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); // Stabilize ROLL axis on 0 degrees banking regardless of loiter radius and position diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 1ee58dbbee3..ebdd30b5ce8 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -138,10 +138,10 @@ static void applyFixedWingLaunchIdleLogic(void) pidResetTPAFilter(); // Throttle control logic - if (navConfig()->fw.launch_idle_throttle <= motorConfig()->minthrottle) + if (navConfig()->fw.launch_idle_throttle <= getThrottleIdleValue()) { ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); // If MOTOR_STOP is enabled mixer will keep motor stopped - rcCommand[THROTTLE] = motorConfig()->minthrottle; // If MOTOR_STOP is disabled, motors will spin at minthrottle + rcCommand[THROTTLE] = getThrottleIdleValue(); // If MOTOR_STOP is disabled, motors will spin at minthrottle } else { @@ -155,7 +155,7 @@ static void applyFixedWingLaunchIdleLogic(void) const float timeSinceMotorStartMs = MIN(millis() - timeThrottleRaisedMs, LAUNCH_MOTOR_IDLE_SPINUP_TIME); rcCommand[THROTTLE] = scaleRangef(timeSinceMotorStartMs, 0.0f, LAUNCH_MOTOR_IDLE_SPINUP_TIME, - motorConfig()->minthrottle, navConfig()->fw.launch_idle_throttle); + getThrottleIdleValue(), navConfig()->fw.launch_idle_throttle); } } } @@ -200,7 +200,7 @@ void applyFixedWingLaunchController(timeUs_t currentTimeUs) // Increase throttle gradually over `launch_motor_spinup_time` milliseconds if (navConfig()->fw.launch_motor_spinup_time > 0) { const float timeSinceMotorStartMs = constrainf(timeElapsedSinceLaunchMs - navConfig()->fw.launch_motor_timer, 0.0f, navConfig()->fw.launch_motor_spinup_time); - const uint16_t minIdleThrottle = MAX(motorConfig()->minthrottle, navConfig()->fw.launch_idle_throttle); + const uint16_t minIdleThrottle = MAX(getThrottleIdleValue(), navConfig()->fw.launch_idle_throttle); rcCommand[THROTTLE] = scaleRangef(timeSinceMotorStartMs, 0.0f, navConfig()->fw.launch_motor_spinup_time, minIdleThrottle, navConfig()->fw.launch_throttle); diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 2c4bca8bb3b..596b47f646b 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -104,7 +104,7 @@ static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros) static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) { // Calculate min and max throttle boundaries (to compensate for integral windup) - const int16_t thrAdjustmentMin = (int16_t)motorConfig()->minthrottle - (int16_t)navConfig()->mc.hover_throttle; + const int16_t thrAdjustmentMin = (int16_t)getThrottleIdleValue() - (int16_t)navConfig()->mc.hover_throttle; const int16_t thrAdjustmentMax = (int16_t)motorConfig()->maxthrottle - (int16_t)navConfig()->mc.hover_throttle; posControl.rcAdjustment[THROTTLE] = navPidApply2(&posControl.pids.vel[Z], posControl.desiredState.vel.z, navGetCurrentActualPositionAndVelocity()->vel.z, US2S(deltaMicros), thrAdjustmentMin, thrAdjustmentMax, 0); @@ -116,7 +116,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) bool adjustMulticopterAltitudeFromRCInput(void) { if (posControl.flags.isTerrainFollowEnabled) { - const float altTarget = scaleRangef(rcCommand[THROTTLE], motorConfig()->minthrottle, motorConfig()->maxthrottle, 0, navConfig()->general.max_terrain_follow_altitude); + const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle, 0, navConfig()->general.max_terrain_follow_altitude); // In terrain follow mode we apply different logic for terrain control if (posControl.flags.estAglStatus == EST_TRUSTED && altTarget > 10.0f) { @@ -144,7 +144,7 @@ bool adjustMulticopterAltitudeFromRCInput(void) } else { // Scaling from minthrottle to altHoldThrottleRCZero - rcClimbRate = rcThrottleAdjustment * navConfig()->general.max_manual_climb_rate / (float)(altHoldThrottleRCZero - motorConfig()->minthrottle - rcControlsConfig()->alt_hold_deadband); + rcClimbRate = rcThrottleAdjustment * navConfig()->general.max_manual_climb_rate / (float)(altHoldThrottleRCZero - getThrottleIdleValue() - rcControlsConfig()->alt_hold_deadband); } updateClimbRateToAltitudeController(rcClimbRate, ROC_TO_ALT_NORMAL); @@ -181,7 +181,7 @@ void setupMulticopterAltitudeController(void) // Make sure we are able to satisfy the deadband altHoldThrottleRCZero = constrain(altHoldThrottleRCZero, - motorConfig()->minthrottle + rcControlsConfig()->alt_hold_deadband + 10, + getThrottleIdleValue() + rcControlsConfig()->alt_hold_deadband + 10, motorConfig()->maxthrottle - rcControlsConfig()->alt_hold_deadband - 10); // Force AH controller to initialize althold integral for pending takeoff on reset @@ -249,7 +249,7 @@ static void applyMulticopterAltitudeController(timeUs_t currentTimeUs) } // Update throttle controller - rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], motorConfig()->minthrottle, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); // Save processed throttle for future use rcCommandAdjustedThrottle = rcCommand[THROTTLE]; @@ -721,12 +721,12 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) } // Update throttle controller - rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], motorConfig()->minthrottle, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); } else { /* Sensors has gone haywire, attempt to land regardless */ if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_DROP_IT) { - rcCommand[THROTTLE] = motorConfig()->minthrottle; + rcCommand[THROTTLE] = getThrottleIdleValue(); } else { rcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index 595dd117d12..cc1e81203f8 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -57,7 +57,6 @@ void targetConfiguration(void) if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED; motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfigMutable()->minthrottle = 1000; } pidProfileMutable()->bank_mc.pid[ROLL].P = 36; diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index 36f871324a7..f57dae63170 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -63,7 +63,6 @@ void targetConfiguration(void) if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->motorPwmProtocol = PWM_TYPE_BRUSHED; motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfigMutable()->minthrottle = 1000; } if (hardwareRevision == AFF4_REV_1) { rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; diff --git a/src/main/target/ALIENFLIGHTNGF7/config.c b/src/main/target/ALIENFLIGHTNGF7/config.c index e11cce5b2fe..3fcda3d1b20 100644 --- a/src/main/target/ALIENFLIGHTNGF7/config.c +++ b/src/main/target/ALIENFLIGHTNGF7/config.c @@ -64,7 +64,6 @@ void targetConfiguration(void) if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfigMutable()->minthrottle = 1000; } if (hardwareRevision == AFF7_REV_1) { diff --git a/src/main/target/ASGARD32F4/config.c b/src/main/target/ASGARD32F4/config.c index 44ba43c0cd5..eb6793cbffb 100644 --- a/src/main/target/ASGARD32F4/config.c +++ b/src/main/target/ASGARD32F4/config.c @@ -37,6 +37,5 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; motorConfigMutable()->motorPwmRate = 4000; - motorConfigMutable()->minthrottle = 1075; motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/ASGARD32F7/config.c b/src/main/target/ASGARD32F7/config.c index 44ba43c0cd5..eb6793cbffb 100644 --- a/src/main/target/ASGARD32F7/config.c +++ b/src/main/target/ASGARD32F7/config.c @@ -37,6 +37,5 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; motorConfigMutable()->motorPwmRate = 4000; - motorConfigMutable()->minthrottle = 1075; motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index 231f0dd6b1b..32aa400b9da 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -82,7 +82,6 @@ void targetConfiguration(void) blackboxConfigMutable()->rate_num = 1; blackboxConfigMutable()->rate_denom = 4; - motorConfigMutable()->minthrottle = 1015; motorConfigMutable()->maxthrottle = 2000; motorConfigMutable()->mincommand = 980; motorConfigMutable()->motorPwmRate = 2000; From c1419b60be44d39ce19daaf26f36dedbaca46348 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 22 Dec 2019 20:56:41 +0000 Subject: [PATCH 075/110] define home offset in cm (vice m) for commonality, if not convenience. --- docs/Cli.md | 2 +- src/main/fc/settings.yaml | 5 ++--- src/main/navigation/navigation.c | 6 +++--- src/main/navigation/navigation.h | 2 +- 4 files changed, 7 insertions(+), 8 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 2d7b9a952fc..57e51070219 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -201,7 +201,7 @@ A shorter form is also supported to enable and disable functions using `serial < | nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | | nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | | nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | | nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | | nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e7aad814fc4..189716b1859 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -80,7 +80,7 @@ tables: - name: debug_modes values: ["NONE", "GYRO", "AGL", "FLOW_RAW", "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", - "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", + "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ"] - name: async_mode values: ["NONE", "GYRO", "ALL"] @@ -1482,11 +1482,10 @@ groups: max: 65000 - name: nav_rth_home_offset_distance field: general.rth_home_offset_distance - max: 650 + max: 65000 - name: nav_rth_home_offset_direction field: general.rth_home_offset_direction max: 359 - - name: nav_mc_bank_angle field: mc.max_bank_angle min: 15 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index b2c91fc1066..0334bc1147d 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -115,7 +115,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .rth_home_altitude = 0, // altitude in centimeters .rth_abort_threshold = 50000, // centimeters - 500m should be safe for all aircraft .max_terrain_follow_altitude = 100, // max altitude in centimeters in terrain following mode - .rth_home_offset_distance = 0, // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) + .rth_home_offset_distance = 0, // Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) .rth_home_offset_direction = 0, // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) }, @@ -2251,8 +2251,8 @@ void updateHomePosition(void) if (setHome) { if (navConfig()->general.rth_home_offset_distance != 0) { // apply user defined offset fpVector3_t offsetHome; - offsetHome.x = posControl.actualState.abs.pos.x + 100 * navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); - offsetHome.y = posControl.actualState.abs.pos.y + 100 * navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + offsetHome.x = posControl.actualState.abs.pos.x + navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); + offsetHome.y = posControl.actualState.abs.pos.y + navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); offsetHome.z = posControl.actualState.abs.pos.z; setHomePosition(&offsetHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); } else { diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 6559fc2bac0..758b47a94e4 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -171,7 +171,7 @@ typedef struct navConfig_s { uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode - uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (metre, 0 disables) + uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) } general; From e81dd408b8ea6ca9f14bdf1753914216c5485ea7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 22 Dec 2019 22:09:53 +0100 Subject: [PATCH 076/110] Change DSHOT throttle scaling to start from min_command, not min_throttle --- src/main/build/debug.h | 1 + src/main/fc/settings.yaml | 2 +- src/main/flight/mixer.c | 19 +++++++++---------- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 4b590d5af4b..fd85fcb7667 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -67,5 +67,6 @@ typedef enum { DEBUG_ERPM, DEBUG_RPM_FILTER, DEBUG_RPM_FREQ, + DEBUG_DSHOT, DEBUG_COUNT } debugType_e; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ee98c5824e2..419286c50b9 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -81,7 +81,7 @@ tables: values: ["NONE", "GYRO", "AGL", "FLOW_RAW", "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", - "ERPM", "RPM_FILTER", "RPM_FREQ"] + "ERPM", "RPM_FILTER", "RPM_FREQ", "DSHOT"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index e8da35a01df..0d897438608 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -85,25 +85,22 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, #ifdef BRUSHED_MOTORS #define DEFAULT_PWM_PROTOCOL PWM_TYPE_BRUSHED #define DEFAULT_PWM_RATE 16000 -#define DEFAULT_MIN_THROTTLE 1000 #else #define DEFAULT_PWM_PROTOCOL PWM_TYPE_STANDARD #define DEFAULT_PWM_RATE 400 -#define DEFAULT_MIN_THROTTLE 1150 #endif #define DEFAULT_MAX_THROTTLE 1850 -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 4); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 5); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = DEFAULT_PWM_PROTOCOL, .motorPwmRate = DEFAULT_PWM_RATE, .maxthrottle = DEFAULT_MAX_THROTTLE, - .mincommand = 1000, + .mincommand = 1000, .motorAccelTimeMs = 0, .motorDecelTimeMs = 0, - .digitalIdleOffsetValue = 450, // Same scale as in Betaflight .throttleIdle = 15.0f, .throttleScale = 1.0f, .motorPoleCount = 14 // Most brushless motors that we use are 14 poles @@ -241,15 +238,14 @@ void FAST_CODE NOINLINE writeMotors(void) #ifdef USE_DSHOT // If we use DSHOT we need to convert motorValue to DSHOT ranges if (isMotorProtocolDigital()) { - const float dshotMinThrottleOffset = (DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 10000.0f * motorConfig()->digitalIdleOffsetValue; if (feature(FEATURE_3D)) { if (motor[i] >= throttleIdleValue && motor[i] <= flight3DConfig()->deadband3d_low) { - motorValue = scaleRangef(motor[i], throttleIdleValue, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, dshotMinThrottleOffset + DSHOT_MIN_THROTTLE); + motorValue = scaleRangef(motor[i], motorConfig()->mincommand, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, DSHOT_MIN_THROTTLE); motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_3D_DEADBAND_LOW); } else if (motor[i] >= flight3DConfig()->deadband3d_high && motor[i] <= motorConfig()->maxthrottle) { - motorValue = scaleRangef(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle, dshotMinThrottleOffset + DSHOT_3D_DEADBAND_HIGH, DSHOT_MAX_THROTTLE); + motorValue = scaleRangef(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle, DSHOT_3D_DEADBAND_HIGH, DSHOT_MAX_THROTTLE); motorValue = constrain(motorValue, DSHOT_3D_DEADBAND_HIGH, DSHOT_MAX_THROTTLE); } else { @@ -261,10 +257,13 @@ void FAST_CODE NOINLINE writeMotors(void) motorValue = DSHOT_DISARM_COMMAND; } else { - motorValue = scaleRangef(motor[i], throttleIdleValue, motorConfig()->maxthrottle, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE); - motorValue = constrain(motorValue, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE); + motorValue = scaleRangef(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE); + motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE); } } + if (i < 4) { + DEBUG_SET(DEBUG_DSHOT, motorCount, motorValue); + } } else { motorValue = motor[i]; From a951e31cd2f777181b53f3e531cf72bf3e8b80b7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 23 Dec 2019 14:12:41 +0100 Subject: [PATCH 077/110] throttleIdleValue as non-static --- src/main/flight/mixer.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 3731088be51..fad91f9764d 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -61,7 +61,7 @@ static float mixerScale = 1.0f; static EXTENDED_FASTRAM motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static EXTENDED_FASTRAM uint8_t motorCount = 0; EXTENDED_FASTRAM int mixerThrottleCommand; -static EXTENDED_FASTRAM int throttleIdleValue = 1150; +EXTENDED_FASTRAM int throttleIdleValue = 1150; PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0); From ae11ad3b748579fd9560f0fa67ba2f715613c349 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 23 Dec 2019 16:35:07 +0100 Subject: [PATCH 078/110] Fix throttle lookup --- src/main/fc/rc_curves.c | 7 ++++--- src/main/flight/mixer.c | 7 +++++-- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c index ff0ce991f9c..7f34607d15b 100644 --- a/src/main/fc/rc_curves.c +++ b/src/main/fc/rc_curves.c @@ -36,12 +36,13 @@ #define YAW_LOOKUP_LENGTH 7 #define THROTTLE_LOOKUP_LENGTH 11 -static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE +static EXTENDED_FASTRAM int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE int16_t lookupThrottleRCMid; // THROTTLE curve mid point void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) { - lookupThrottleRCMid = getThrottleIdleValue() + (int32_t)(motorConfig()->maxthrottle - getThrottleIdleValue()) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] + const int minThrottle = getThrottleIdleValue(); + lookupThrottleRCMid = minThrottle + (int32_t)(motorConfig()->maxthrottle - minThrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { const int16_t tmp = 10 * i - controlRateConfig->throttle.rcMid8; @@ -51,7 +52,7 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) if (tmp < 0) y = controlRateConfig->throttle.rcMid8; lookupThrottleRC[i] = 10 * controlRateConfig->throttle.rcMid8 + tmp * (100 - controlRateConfig->throttle.rcExpo8 + (int32_t) controlRateConfig->throttle.rcExpo8 * (tmp * tmp) / (y * y)) / 10; - lookupThrottleRC[i] = getThrottleIdleValue() + (int32_t) (motorConfig()->maxthrottle - getThrottleIdleValue()) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRC[i] = minThrottle + (int32_t) (motorConfig()->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } } diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index fad91f9764d..6e12e58f639 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -61,7 +61,7 @@ static float mixerScale = 1.0f; static EXTENDED_FASTRAM motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static EXTENDED_FASTRAM uint8_t motorCount = 0; EXTENDED_FASTRAM int mixerThrottleCommand; -EXTENDED_FASTRAM int throttleIdleValue = 1150; +static EXTENDED_FASTRAM int throttleIdleValue = 0; PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0); @@ -112,6 +112,10 @@ static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn; int getThrottleIdleValue(void) { + if (!throttleIdleValue) { + throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * motorConfig()->throttleIdle); + } + return throttleIdleValue; } @@ -204,7 +208,6 @@ void applyMotorRateLimiting(const float dT) void mixerInit(void) { - throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * motorConfig()->throttleIdle); computeMotorCount(); loadPrimaryMotorMixer(); // in 3D mode, mixer gain has to be halved From 6bac376bcc79c01ecf71a0040cc84618d91d9eb7 Mon Sep 17 00:00:00 2001 From: hali9 Date: Wed, 25 Dec 2019 16:25:51 +0100 Subject: [PATCH 079/110] fix wp linear climb dive --- src/main/navigation/navigation.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 0334bc1147d..3cfe2459ef1 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1399,8 +1399,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na fpVector3_t tmpWaypoint; tmpWaypoint.x = posControl.activeWaypoint.pos.x; tmpWaypoint.y = posControl.activeWaypoint.pos.y; - tmpWaypoint.z = scaleRange(constrainf(posControl.wpDistance, posControl.wpInitialDistance / 10, posControl.wpInitialDistance), - posControl.wpInitialDistance, posControl.wpInitialDistance / 10, + tmpWaypoint.z = scaleRangef(constrainf(posControl.wpDistance, posControl.wpInitialDistance / 10.0f, posControl.wpInitialDistance), + posControl.wpInitialDistance, posControl.wpInitialDistance / 10.0f, posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z); setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING); return NAV_FSM_EVENT_NONE; // will re-process state in >10ms From 8f21b1be9c5e6487265cb711253984c7d05a3465 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 29 Dec 2019 12:37:50 +0000 Subject: [PATCH 080/110] update Cli.md for `throttle_idle`, remove `min_throttle`, remove or update references --- docs/Cli.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 57e51070219..64799baab90 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -138,8 +138,8 @@ A shorter form is also supported to enable and disable functions using `serial < | rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | | rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | | input_filtering_mode | OFF | Filter out noise from OpenLRS Telemetry RX | -| min_throttle | 1150 | These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. | -| max_throttle | 1850 | These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. If you have brushed motors, the value should be set to 2000. | +| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | +| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. | | min_command | 1000 | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. | | 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) | | 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | @@ -221,9 +221,9 @@ A shorter form is also supported to enable and disable functions using `serial < | nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | | nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | | nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below min_throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above min_throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | +| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | | nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | Time to bring power from min_throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | +| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | | nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) | | nav_fw_launch_max_altitude | 0 | Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. [cm] | | nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | From 793730fae438e310f597479fcf187023b07d7109 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 29 Dec 2019 22:06:16 +0000 Subject: [PATCH 081/110] update `docs/Controls.md` for `throttle_idle` --- docs/Controls.md | 33 +++++++++++++-------------------- 1 file changed, 13 insertions(+), 20 deletions(-) diff --git a/docs/Controls.md b/docs/Controls.md index 40132923da3..7b3e8705975 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -2,12 +2,9 @@ ## Arming -When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. The motors will -spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, -that is not recommended). +When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. The motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended). -By default, arming and disarming is done using stick positions. (NOTE: this feature is disabled when using a -switch to arm.) +By default, arming and disarming is done using stick positions. (NOTE: this feature is disabled when using a switch to arm.) ## Stick Positions @@ -45,14 +42,9 @@ The stick positions are combined to activate different functions: ## Yaw control -While arming/disarming with sticks, your yaw stick will be moving to extreme values. In order to prevent your craft -from trying to yaw during arming/disarming while on the ground, your yaw input will not cause the craft to yaw when the -throttle is LOW (i.e. below the `min_check` setting). +While arming/disarming with sticks, your yaw stick will be moving to extreme values. In order to prevent your craft from trying to yaw during arming/disarming while on the ground, your yaw input will not cause the craft to yaw when the throttle is LOW (i.e. below the `min_check` setting). -For tricopters, you may want to retain the ability to yaw while on the ground, so that you can verify that your tail -servo is working correctly before takeoff. You can do this by setting `tri_unarmed_servo` to `1` on the CLI (this is the -default). If you are having issues with your tail rotor contacting the ground during arm/disarm, you can set this to -`0` instead. Check this table to decide which setting will suit you: +For tricopters, you may want to retain the ability to yaw while on the ground, so that you can verify that your tail servo is working correctly before takeoff. You can do this by setting `tri_unarmed_servo` to `1` on the CLI (this is the default). If you are having issues with your tail rotor contacting the ground during arm/disarm, you can set this to `0` instead. Check this table to decide which setting will suit you: @@ -78,23 +70,24 @@ default). If you are having issues with your tail rotor contacting the ground du
- ## Throttle settings and their interaction +*Terminology. After iNav 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.* + `min_command` - -With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety. +With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety. -`min_check` - -With switch arming mode is in use, lowering your throttle below min_check will result in motors spinning at min_throttle. When using the default stick arming, lowering your throttle below min_check will result in motors spinning at min_throttle and yaw being disabled so that you may arm/disarm. With motor stop enabled, lowering your throttle below min_check will also result in motors off and the esc's being sent min_command. Min_check must be set to a level that is 100% reliably met by the throttle throw. A setting too low may result in a dangerous condition where the copter can’t be disarmed. It is ok to set this below min_throttle because the FC will automaticly scale the output to the esc's +`min_check` - +With switch arming mode is in use, lowering your throttle below min_check will result in motors spinning at `throttle_idle` (min_throttle). When using the default stick arming, lowering your throttle below min_check will result in motors spinning at min_throttle and yaw being disabled so that you may arm/disarm. With motor stop enabled, lowering your throttle below min_check will also result in motors off and the esc's being sent min_command. Min_check must be set to a level that is 100% reliably met by the throttle throw. A setting too low may result in a dangerous condition where the copter can’t be disarmed. It is ok to set this below `throttle_idle` (min_throttle) because the FC will automaticly scale the output to the ESCs -`min_throttle` - -Typically set to just above reliable spin up of all motors. Sometimes this is set slightly higher for prop stall prevention during advanced maneuvers or sometimes considerably higher to produce a desired result. When armed with motor stop off, your motors will spin at this command so keep that in mind from a safety stand point. +`throttle_idle` (previously `min_throttle)` - +Typically set to just above reliable spin up of all motors. Sometimes this is set slightly higher for prop stall prevention during advanced maneuvers or sometimes considerably higher to produce a desired result. When armed with motor stop off, your motors will spin at this command so keep that in mind from a safety stand point. `max_check` - -Throttle positions above this level will send max_command to the esc's. +Throttle positions above this level will send max_command to the ESCs. `max_throttle` - -This is the max command to the esc's from the flight controller. +This is the max command to the ESCs from the flight controller. In depth videos explaining these terms are available from Joshua Bardwell here: From e4680a4b3c862614f9e800b23be9d85d601d554d Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sun, 29 Dec 2019 20:08:17 +0100 Subject: [PATCH 082/110] [DJI] Initial cut on DJI HD goggles special MSP flavour --- make/source.mk | 1 + src/main/fc/fc_init.c | 6 + src/main/fc/fc_tasks.c | 6 + src/main/fc/runtime_config.c | 11 +- src/main/fc/runtime_config.h | 2 + src/main/io/osd_dji_hd.c | 554 +++++++++++++++++++++++++++++++ src/main/io/osd_dji_hd.h | 62 ++++ src/main/io/serial.h | 1 + src/main/msp/msp_serial.c | 71 ++-- src/main/msp/msp_serial.h | 3 + src/main/target/common.h | 1 + src/main/telemetry/ibus_shared.c | 6 +- src/main/telemetry/sim.c | 2 +- 13 files changed, 684 insertions(+), 42 deletions(-) create mode 100644 src/main/io/osd_dji_hd.c create mode 100644 src/main/io/osd_dji_hd.h diff --git a/make/source.mk b/make/source.mk index 55d4a9470b8..4fb7f2618a8 100644 --- a/make/source.mk +++ b/make/source.mk @@ -101,6 +101,7 @@ COMMON_SRC = \ io/beeper.c \ io/esc_serialshot.c \ io/frsky_osd.c \ + io/osd_dji_hd.c \ io/lights.c \ io/piniobox.c \ io/pwmdriver_i2c.c \ diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index e2066da47e2..0e706cd99e8 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -108,6 +108,7 @@ #include "io/ledstrip.h" #include "io/pwmdriver_i2c.h" #include "io/osd.h" +#include "io/osd_dji_hd.h" #include "io/rcdevice_cam.h" #include "io/serial.h" #include "io/displayport_msp.h" @@ -265,6 +266,11 @@ void init(void) // to run after the sensors have been detected. mspSerialInit(); +#if defined(USE_DJI_HD_OSD) + // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task + djiOsdSerialInit(); +#endif + #if defined(USE_LOG) // LOG might use serial output, so we only can init it after serial port is ready // From this point on we can use LOG_*() to produce real-time debugging information diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index dc50a4126e1..e8ba6f432a5 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -61,6 +61,7 @@ #include "io/serial.h" #include "io/rcdevice_cam.h" #include "io/vtx.h" +#include "io/osd_dji_hd.h" #include "msp/msp_serial.h" @@ -97,6 +98,11 @@ void taskHandleSerial(timeUs_t currentTimeUs) // Allow MSP processing even if in CLI mode mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand); + +#if defined(USE_DJI_HD_OSD) + // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task + djiOsdSerialProcess(); +#endif } void taskUpdateBattery(timeUs_t currentTimeUs) diff --git a/src/main/fc/runtime_config.c b/src/main/fc/runtime_config.c index 8540e7b3175..0d1a60a25cc 100644 --- a/src/main/fc/runtime_config.c +++ b/src/main/fc/runtime_config.c @@ -102,18 +102,21 @@ uint32_t sensorsMask(void) flightModeForTelemetry_e getFlightModeForTelemetry(void) { - if (FLIGHT_MODE(MANUAL_MODE)) - return FLM_MANUAL; - if (FLIGHT_MODE(FAILSAFE_MODE)) return FLM_FAILSAFE; + if (FLIGHT_MODE(MANUAL_MODE)) + return FLM_MANUAL; + if (FLIGHT_MODE(NAV_RTH_MODE)) return FLM_RTH; if (FLIGHT_MODE(NAV_POSHOLD_MODE)) return FLM_POSITION_HOLD; + if (FLIGHT_MODE(NAV_CRUISE_MODE)) + return FLM_CRUISE; + if (FLIGHT_MODE(NAV_WP_MODE)) return FLM_MISSION; @@ -129,5 +132,5 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void) if (FLIGHT_MODE(NAV_LAUNCH_MODE)) return FLM_LAUNCH; - return FLM_ACRO; + return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO; } diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index f97b499ea0b..c97e911ed9e 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -134,12 +134,14 @@ extern uint32_t stateFlags; typedef enum { FLM_MANUAL, FLM_ACRO, + FLM_ACRO_AIR, FLM_ANGLE, FLM_HORIZON, FLM_ALTITUDE_HOLD, FLM_POSITION_HOLD, FLM_RTH, FLM_MISSION, + FLM_CRUISE, FLM_LAUNCH, FLM_FAILSAFE, FLM_COUNT diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c new file mode 100644 index 00000000000..0f9e2573553 --- /dev/null +++ b/src/main/io/osd_dji_hd.c @@ -0,0 +1,554 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + * + * @author Konstantin Sharlaimov (ksharlaimov@inavflight.com) + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/debug.h" +#include "build/version.h" + +#include "common/streambuf.h" +#include "common/utils.h" +#include "common/maths.h" +#include "common/time.h" +#include "common/crc.h" + +#include "fc/fc_core.h" +#include "fc/config.h" +#include "fc/fc_msp.h" +#include "fc/fc_msp_box.h" +#include "fc/runtime_config.h" + +#include "flight/imu.h" +#include "flight/pid.h" + +#include "io/serial.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/osd_dji_hd.h" + +#include "rx/rx.h" + +#include "sensors/sensors.h" +#include "sensors/battery.h" + +#include "msp/msp.h" +#include "msp/msp_protocol.h" +#include "msp/msp_serial.h" + +#include "navigation/navigation.h" + +#include "scheduler/scheduler.h" + + +#define DJI_MSP_BAUDRATE 115200 + +#define DJI_ARMING_DISABLE_FLAGS_COUNT 25 +#define DJI_OSD_WARNING_COUNT 16 +#define DJI_OSD_TIMER_COUNT 2 +#define DJI_OSD_FLAGS_OSD_FEATURE (1 << 0) + +/* + * DJI HD goggles use MSPv1 compatible with Betaflight 4.1.0 + * DJI uses a subset of messages and assume fixed bit positions for flight modes + * + * To avoid compatibility issues we maintain a separate MSP command processor + * but reuse the packet decoder to minimize code duplication + */ + +// External dependency on looptime +extern timeDelta_t cycleTime; + +// MSP packet decoder state structure +static mspPort_t djiMspPort; + +// Mapping table between DJI PID and INAV PID (order is different) +const uint8_t djiPidIndexMap[] = { + PID_ROLL, // DJI: PID_ROLL + PID_PITCH, // DJI: PID_PITCH + PID_YAW, // DJI: PID_YAW + PID_LEVEL, // DJI: PID_LEVEL + PID_HEADING // DJI: PID_MAG +}; + +const int djiOSDItemIndexMap[] = { + OSD_RSSI_VALUE, // DJI: OSD_RSSI_VALUE + OSD_MAIN_BATT_VOLTAGE, // DJI: OSD_MAIN_BATT_VOLTAGE + OSD_CROSSHAIRS, // DJI: OSD_CROSSHAIRS + OSD_ARTIFICIAL_HORIZON, // DJI: OSD_ARTIFICIAL_HORIZON + OSD_HORIZON_SIDEBARS, // DJI: OSD_HORIZON_SIDEBARS + OSD_ONTIME, // DJI: OSD_ITEM_TIMER_1 + OSD_FLYTIME, // DJI: OSD_ITEM_TIMER_2 + OSD_FLYMODE, // DJI: OSD_FLYMODE + OSD_CRAFT_NAME, // DJI: OSD_CRAFT_NAME + OSD_THROTTLE_POS, // DJI: OSD_THROTTLE_POS + OSD_VTX_CHANNEL, // DJI: OSD_VTX_CHANNEL + OSD_CURRENT_DRAW, // DJI: OSD_CURRENT_DRAW + OSD_MAH_DRAWN, // DJI: OSD_MAH_DRAWN + OSD_GPS_SPEED, // DJI: OSD_GPS_SPEED + OSD_GPS_SATS, // DJI: OSD_GPS_SATS + OSD_ALTITUDE, // DJI: OSD_ALTITUDE + OSD_ROLL_PIDS, // DJI: OSD_ROLL_PIDS + OSD_PITCH_PIDS, // DJI: OSD_PITCH_PIDS + OSD_YAW_PIDS, // DJI: OSD_YAW_PIDS + OSD_POWER, // DJI: OSD_POWER + -1, // DJI: OSD_PIDRATE_PROFILE + -1, // DJI: OSD_WARNINGS + OSD_MAIN_BATT_CELL_VOLTAGE, // DJI: OSD_AVG_CELL_VOLTAGE + OSD_GPS_LON, // DJI: OSD_GPS_LON + OSD_GPS_LAT, // DJI: OSD_GPS_LAT + OSD_DEBUG, // DJI: OSD_DEBUG + OSD_ATTITUDE_PITCH, // DJI: OSD_PITCH_ANGLE + OSD_ATTITUDE_ROLL, // DJI: OSD_ROLL_ANGLE + -1, // DJI: OSD_MAIN_BATT_USAGE + -1, // DJI: OSD_DISARMED + OSD_HOME_DIR, // DJI: OSD_HOME_DIR + OSD_HOME_DIST, // DJI: OSD_HOME_DIST + OSD_HEADING, // DJI: OSD_NUMERICAL_HEADING + OSD_VARIO_NUM, // DJI: OSD_NUMERICAL_VARIO + -1, // DJI: OSD_COMPASS_BAR + -1, // DJI: OSD_ESC_TMP + OSD_ESC_RPM, // DJI: OSD_ESC_RPM + OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, // DJI: OSD_REMAINING_TIME_ESTIMATE + OSD_RTC_TIME, // DJI: OSD_RTC_DATETIME + -1, // DJI: OSD_ADJUSTMENT_RANGE + -1, // DJI: OSD_CORE_TEMPERATURE + -1, // DJI: OSD_ANTI_GRAVITY + -1, // DJI: OSD_G_FORCE + -1, // DJI: OSD_MOTOR_DIAG + -1, // DJI: OSD_LOG_STATUS + -1, // DJI: OSD_FLIP_ARROW + -1, // DJI: OSD_LINK_QUALITY + OSD_TRIP_DIST, // DJI: OSD_FLIGHT_DIST + -1, // DJI: OSD_STICK_OVERLAY_LEFT + -1, // DJI: OSD_STICK_OVERLAY_RIGHT + -1, // DJI: OSD_DISPLAY_NAME + -1, // DJI: OSD_ESC_RPM_FREQ + -1, // DJI: OSD_RATE_PROFILE_NAME + -1, // DJI: OSD_PID_PROFILE_NAME + -1, // DJI: OSD_PROFILE_NAME + -1, // DJI: OSD_RSSI_DBM_VALUE + -1, // DJI: OSD_RC_CHANNELS +}; + +const int djiOSDStatisticsMap[] = { + -1, // DJI: OSD_STAT_RTC_DATE_TIME + -1, // DJI: OSD_STAT_TIMER_1 + -1, // DJI: OSD_STAT_TIMER_2 + -1, // DJI: OSD_STAT_MAX_SPEED + -1, // DJI: OSD_STAT_MAX_DISTANCE + -1, // DJI: OSD_STAT_MIN_BATTERY + -1, // DJI: OSD_STAT_END_BATTERY + -1, // DJI: OSD_STAT_BATTERY + -1, // DJI: OSD_STAT_MIN_RSSI + -1, // DJI: OSD_STAT_MAX_CURRENT + -1, // DJI: OSD_STAT_USED_MAH + -1, // DJI: OSD_STAT_MAX_ALTITUDE + -1, // DJI: OSD_STAT_BLACKBOX + -1, // DJI: OSD_STAT_BLACKBOX_NUMBER + -1, // DJI: OSD_STAT_MAX_G_FORCE + -1, // DJI: OSD_STAT_MAX_ESC_TEMP + -1, // DJI: OSD_STAT_MAX_ESC_RPM + -1, // DJI: OSD_STAT_MIN_LINK_QUALITY + -1, // DJI: OSD_STAT_FLIGHT_DISTANCE + -1, // DJI: OSD_STAT_MAX_FFT + -1, // DJI: OSD_STAT_TOTAL_FLIGHTS + -1, // DJI: OSD_STAT_TOTAL_TIME + -1, // DJI: OSD_STAT_TOTAL_DIST + -1, // DJI: OSD_STAT_MIN_RSSI_DBM +}; + +void djiOsdSerialInit(void) +{ + memset(&djiMspPort, 0, sizeof(mspPort_t)); + + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_DJI_HD_OSD); + + if (!portConfig) { + return; + } + + serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_DJI_HD_OSD, NULL, NULL, DJI_MSP_BAUDRATE, MODE_RXTX, SERIAL_NOT_INVERTED); + + if (serialPort) { + resetMspPort(&djiMspPort, serialPort); + } +} + +static void djiPackBoxModeBitmask(boxBitmask_t * flightModeBitmask) +{ + memset(flightModeBitmask, 0, sizeof(boxBitmask_t)); + + switch(getFlightModeForTelemetry()) { + case FLM_MANUAL: + case FLM_ACRO: + case FLM_ACRO_AIR: + // DJI: No bits set = ACRO + break; + case FLM_ANGLE: + bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE + break; + case FLM_HORIZON: + bitArraySet(flightModeBitmask->bits, 2); // DJI: 1 << 2 + break; + case FLM_RTH: + bitArraySet(flightModeBitmask->bits, 5); // DJI: 1 << 5 : GPS_RESQUE + break; + case FLM_CRUISE: + bitArraySet(flightModeBitmask->bits, 3); // DJI: 1 << 3 : technically HEADFREE + break; + case FLM_FAILSAFE: + bitArraySet(flightModeBitmask->bits, 4); // DJI: 1 << 4 + break; + case FLM_LAUNCH: + case FLM_ALTITUDE_HOLD: + case FLM_POSITION_HOLD: + case FLM_MISSION: + default: + // Unsupported ATM, keep at ANGLE + bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE + } +} + +static uint32_t djiPackArmingDisabledFlags(void) +{ + // TODO: Map INAV arming disabled flags to DJI/BF ones + // https://github.com/betaflight/betaflight/blob/c6e5882dd91fa20d246b8f8af10cf6c92876bc3d/src/main/fc/runtime_config.h#L42 + // For now hide everything in ARMING_DISABLED_ARM_SWITCH (bit 24) + + return isArmingDisabled() ? (1 << 24) : 0; +} + +static uint32_t djiEncodeOSDEnabledWarnings(void) +{ + // TODO: + return 0; +} + +static void djiSerializeOSDConfigReply(sbuf_t *dst) +{ + // Only send supported flag - always + sbufWriteU8(dst, DJI_OSD_FLAGS_OSD_FEATURE); + + // 7456 video system (AUTO/PAL/NTSC) + sbufWriteU8(dst, osdConfig()->video_system); + + // Configuration + sbufWriteU8(dst, osdConfig()->units); + + // Alarms + sbufWriteU8(dst, osdConfig()->rssi_alarm); + sbufWriteU16(dst, currentBatteryProfile->capacity.warning); + + // OSD_ITEM_COUNT (previously was timer alarm) + sbufWriteU8(dst, 0); + sbufWriteU8(dst, ARRAYLEN(djiOSDItemIndexMap)); + + // Altitude alarm + sbufWriteU16(dst, osdConfig()->alt_alarm); + + // OSD element position and visibility + for (unsigned i = 0; i < ARRAYLEN(djiOSDItemIndexMap); i++) { + int inavOSDIdx = djiOSDItemIndexMap[i]; + if (inavOSDIdx >= 0) { + // Position & visibility encoded in 16 bits. Position encoding is the same between BF/DJI and INAV + // However visibility is different. INAV has 3 layouts, while BF only has visibility profiles + // Here we use only one OSD layout mapped to first OSD BF profile + uint16_t itemPos = osdConfig()->item_pos[0][inavOSDIdx]; + + // Workarounds for certain OSD element positions + // INAV calculates these dynamically, while DJI expects the config to have defined coordinates + switch(inavOSDIdx) { + case OSD_CROSSHAIRS: + itemPos = (itemPos & (~OSD_POS_MAX)) | OSD_POS(13, 6); + break; + + case OSD_ARTIFICIAL_HORIZON: + itemPos = (itemPos & (~OSD_POS_MAX)) | OSD_POS(14, 2); + break; + + case OSD_HORIZON_SIDEBARS: + itemPos = (itemPos & (~OSD_POS_MAX)) | OSD_POS(14, 5); + break; + } + + // Enforce visibility in 3 BF OSD profiles + if (OSD_VISIBLE(itemPos)) { + itemPos |= 0x3000; + } + + sbufWriteU16(dst, itemPos); + } + else { + // Hide OSD elements unsupported by INAV + sbufWriteU16(dst, 0); + } + } + + // Post flight statistics + sbufWriteU8(dst, ARRAYLEN(djiOSDStatisticsMap)); + for (unsigned i = 0; i < ARRAYLEN(djiOSDStatisticsMap); i++ ) { + if (djiOSDStatisticsMap[i] >= 0) { + // FIXME: Map post-flight statistics from INAV to BF/DJI + sbufWriteU8(dst, 0); + } + else { + sbufWriteU8(dst, 0); + } + } + + // Timers + sbufWriteU8(dst, DJI_OSD_TIMER_COUNT); + for (int i = 0; i < DJI_OSD_TIMER_COUNT; i++) { + // STUB: We don't support BF's OSD timers + sbufWriteU16(dst, 0); + } + + // Enabled warnings + // API < 1.41 stub, kept for compatibility + sbufWriteU16(dst, djiEncodeOSDEnabledWarnings() & 0xFFFF); + + // API >= 1.41 + // Send the warnings count and 32bit enabled warnings flags. + sbufWriteU8(dst, DJI_OSD_WARNING_COUNT); + sbufWriteU32(dst, djiEncodeOSDEnabledWarnings()); + + // DJI OSD expects 1 OSD profile + sbufWriteU8(dst, 1); + sbufWriteU8(dst, 1); + + // No OSD stick overlay + sbufWriteU8(dst, 0); + + // API >= 1.43 + // Camera frame element width/height - magic numbers taken from Betaflight source + //sbufWriteU8(dst, DJI_OSD_SCREEN_WIDTH); // osdConfig()->camera_frame_width + //sbufWriteU8(dst, DJI_OSD_SCREEN_HEIGHT); // osdConfig()->camera_frame_height +} + +static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) +{ + UNUSED(mspPostProcessFn); + + sbuf_t *dst = &reply->buf; + //sbuf_t *src = &cmd->buf; + + // Start initializing the reply message + reply->cmd = cmd->cmd; + reply->result = MSP_RESULT_ACK; + + switch (cmd->cmd) { + case DJI_MSP_API_VERSION: + sbufWriteU8(dst, MSP_PROTOCOL_VERSION); + sbufWriteU8(dst, DJI_API_VERSION_MAJOR); + sbufWriteU8(dst, DJI_API_VERSION_MINOR); + break; + + case DJI_MSP_FC_VARIANT: + { + const char * const flightControllerIdentifier = INAV_IDENTIFIER; + sbufWriteData(dst, flightControllerIdentifier, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH); + } + break; + + case DJI_MSP_FC_VERSION: + sbufWriteU8(dst, 4); + sbufWriteU8(dst, 1); + sbufWriteU8(dst, 0); + break; + + case DJI_MSP_NAME: + for (const char * name = systemConfig()->name; *name; name++) { + sbufWriteU8(dst, *name++); + } + break; + + case DJI_MSP_STATUS: + case DJI_MSP_STATUS_EX: + { + // DJI OSD relies on a statically defined bit order and doesn't use MSP_BOXIDS + // to get actual BOX order. We need a special packBoxModeFlags() + boxBitmask_t flightModeBitmask; + djiPackBoxModeBitmask(&flightModeBitmask); + + sbufWriteU16(dst, (uint16_t)cycleTime); + sbufWriteU16(dst, 0); + sbufWriteU16(dst, packSensorStatus()); + sbufWriteData(dst, &flightModeBitmask, 4); // unconditional part of flags, first 32 bits + sbufWriteU8(dst, getConfigProfile()); + + sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100)); + if (cmd->cmd == MSP_STATUS_EX) { + sbufWriteU8(dst, 3); // PID_PROFILE_COUNT + sbufWriteU8(dst, 1); // getCurrentControlRateProfileIndex() + } else { + sbufWriteU16(dst, cycleTime); // gyro cycle time + } + + // Cap BoxModeFlags to 32 bits + // write flightModeFlags header. Lowest 4 bits contain number of bytes that follow + sbufWriteU8(dst, 0); + // sbufWriteData(dst, ((uint8_t*)&flightModeBitmask) + 4, byteCount); + + // Write arming disable flags + sbufWriteU8(dst, DJI_ARMING_DISABLE_FLAGS_COUNT); + sbufWriteU32(dst, djiPackArmingDisabledFlags()); + + // Extra flags + sbufWriteU8(dst, 0); + } + break; + + case DJI_MSP_RC: + // Only send sticks (first 4 channels) + for (int i = 0; i < STICK_CHANNEL_COUNT; i++) { + sbufWriteU16(dst, rxGetRawChannelValue(i)); + } + break; + + case DJI_MSP_RAW_GPS: + sbufWriteU8(dst, gpsSol.fixType); + sbufWriteU8(dst, gpsSol.numSat); + sbufWriteU32(dst, gpsSol.llh.lat); + sbufWriteU32(dst, gpsSol.llh.lon); + sbufWriteU16(dst, gpsSol.llh.alt / 100); + sbufWriteU16(dst, gpsSol.groundSpeed); + sbufWriteU16(dst, gpsSol.groundCourse); + break; + + case DJI_MSP_COMP_GPS: + sbufWriteU16(dst, GPS_distanceToHome); + sbufWriteU16(dst, GPS_directionToHome); + sbufWriteU8(dst, gpsSol.flags.gpsHeartbeat ? 1 : 0); + break; + + case DJI_MSP_ATTITUDE: + sbufWriteU16(dst, attitude.values.roll); + sbufWriteU16(dst, attitude.values.pitch); + sbufWriteU16(dst, DECIDEGREES_TO_DEGREES(attitude.values.yaw)); + break; + + case DJI_MSP_ALTITUDE: + sbufWriteU32(dst, lrintf(getEstimatedActualPosition(Z))); + sbufWriteU16(dst, lrintf(getEstimatedActualVelocity(Z))); + break; + + case DJI_MSP_ANALOG: + sbufWriteU8(dst, constrain(getBatteryVoltage() / 10, 0, 255)); + sbufWriteU16(dst, constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery + sbufWriteU16(dst, getRSSI()); + sbufWriteU16(dst, constrain(getAmperage(), -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A + sbufWriteU16(dst, getBatteryVoltage()); + break; + + case DJI_MSP_PID: + for (unsigned i = 0; i < ARRAYLEN(djiPidIndexMap); i++) { + sbufWriteU8(dst, pidBank()->pid[djiPidIndexMap[i]].P); + sbufWriteU8(dst, pidBank()->pid[djiPidIndexMap[i]].I); + sbufWriteU8(dst, pidBank()->pid[djiPidIndexMap[i]].D); + } + break; + + case DJI_MSP_BATTERY_STATE: + // Battery characteristics + sbufWriteU8(dst, constrain(getBatteryCellCount(), 0, 255)); + sbufWriteU16(dst, currentBatteryProfile->capacity.value); + + // Battery state + sbufWriteU8(dst, constrain(getBatteryVoltage() / 10, 0, 255)); // in 0.1V steps + sbufWriteU16(dst, constrain(getMAhDrawn(), 0, 0xFFFF)); + sbufWriteU16(dst, constrain(getAmperage(), -0x8000, 0x7FFF)); + + // Battery alerts - used values match Betaflight's/DJI's + sbufWriteU8(dst, getBatteryState()); + + // Additional battery voltage field (in 0.01V steps) + sbufWriteU16(dst, getBatteryVoltage()); + break; + + case DJI_MSP_RTC: + { + dateTime_t datetime; + + // We don't care about validity here - dt will be always set to a sane value + // rtcGetDateTime() will call rtcGetDefaultDateTime() internally + rtcGetDateTime(&datetime); + + sbufWriteU16(dst, datetime.year); + sbufWriteU8(dst, datetime.month); + sbufWriteU8(dst, datetime.day); + sbufWriteU8(dst, datetime.hours); + sbufWriteU8(dst, datetime.minutes); + sbufWriteU8(dst, datetime.seconds); + sbufWriteU16(dst, datetime.millis); + } + break; + + case DJI_MSP_OSD_CONFIG: +#if defined(USE_OSD) + // This involved some serious magic, better contain in a separate function for readability + djiSerializeOSDConfigReply(dst); +#else + sbufWriteU8(dst, 0); +#endif + break; + + case DJI_MSP_FILTER_CONFIG: + case DJI_MSP_PID_ADVANCED: + case DJI_MSP_RC_TUNING: + case DJI_MSP_ESC_SENSOR_DATA: + // TODO + reply->result = MSP_RESULT_ERROR; + break; + + default: + debug[1]++; + debug[2] = cmd->cmd; + reply->result = MSP_RESULT_ERROR; + break; + } + + // Process DONT_REPLY flag + if (cmd->flags & MSP_FLAG_DONT_REPLY) { + reply->result = MSP_RESULT_NO_REPLY; + } + + return reply->result; +} + +void djiOsdSerialProcess(void) +{ + // Check if DJI OSD is configured + if (!djiMspPort.port) { + return; + } + + // Piggyback on existing MSP protocol stack, but pass our special command processing function + mspSerialProcessOnePort(&djiMspPort, MSP_SKIP_NON_MSP_DATA, djiProcessMspCommand); +} \ No newline at end of file diff --git a/src/main/io/osd_dji_hd.h b/src/main/io/osd_dji_hd.h new file mode 100644 index 00000000000..97dddf9857b --- /dev/null +++ b/src/main/io/osd_dji_hd.h @@ -0,0 +1,62 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + * + * @author Konstantin Sharlaimov (ksharlaimov@inavflight.com) + */ + +#pragma once + +#include "msp/msp.h" +#include "msp/msp_serial.h" + +#if defined(USE_DJI_HD_OSD) + +#define DJI_API_VERSION_MAJOR 1 +#define DJI_API_VERSION_MINOR 42 + +#define DJI_MSP_API_VERSION 1 // INAV: Implemented | DSI: ??? | +#define DJI_MSP_FC_VARIANT 2 // INAV: Implemented | DSI: ??? | +#define DJI_MSP_FC_VERSION 3 // INAV: Implemented | DSI: ??? | +#define DJI_MSP_NAME 10 // INAV: Implemented | DSI: Implemented | For OSD 'Craft Name' +#define DJI_MSP_OSD_CONFIG 84 // INAV: Implemented | DSI: Implemented | OSD item count + positions +#define DJI_MSP_FILTER_CONFIG 92 // INAV: Not implemented | DSI: Implemented | +#define DJI_MSP_PID_ADVANCED 94 // INAV: Not implemented | DSI: Implemented | +#define DJI_MSP_STATUS 101 // INAV: Implemented | DSI: Implemented | For OSD ‘armingTime’, Flight controller arming status +#define DJI_MSP_RC 105 // INAV: Implemented | DSI: Implemented | +#define DJI_MSP_RAW_GPS 106 // INAV: Implemented | DSI: Implemented | For OSD ‘GPS Sats’ + coordinates +#define DJI_MSP_COMP_GPS 107 // INAV: Implemented | DSI: Not implemented | GPS direction to home & distance to home +#define DJI_MSP_ATTITUDE 108 // INAV: Implemented | DSI: Implemented | For OSD ‘Angle: roll & pitch’ +#define DJI_MSP_ALTITUDE 109 // INAV: Implemented | DSI: Implemented | For OSD ‘Numerical Vario’ +#define DJI_MSP_ANALOG 110 // INAV: Implemented | DSI: Implemented | For OSD ‘RSSI Value’, For OSD ‘Battery voltage’ etc +#define DJI_MSP_RC_TUNING 111 // INAV: Not implemented | DSI: Implemented | +#define DJI_MSP_PID 112 // INAV: Implemented | DSI: Implemented | For OSD ‘PID roll, yaw, pitch' +#define DJI_MSP_BATTERY_STATE 130 // INAV: Implemented | DSI: Implemented | For OSD ‘Battery current mAh drawn’ etc +#define DJI_MSP_ESC_SENSOR_DATA 134 // INAV: Implemented | DSI: Implemented | For OSD ‘ESC temperature’ +#define DJI_MSP_STATUS_EX 150 // INAV: Implemented | DSI: Implemented | For OSD ‘Fly mode', For OSD ‘Disarmed’ +#define DJI_MSP_RTC 247 // INAV: Implemented | DSI: Implemented | For OSD ‘RTC date time’ + + +void djiOsdSerialInit(void); +void djiOsdSerialProcess(void); + +#endif \ No newline at end of file diff --git a/src/main/io/serial.h b/src/main/io/serial.h index afd2d6c584b..bea6abb0016 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -52,6 +52,7 @@ typedef enum { FUNCTION_ESCSERIAL = (1 << 18), // 262144: this is used for both SERIALSHOT and ESC_SENSOR telemetry FUNCTION_TELEMETRY_SIM = (1 << 19), // 524288 FUNCTION_FRSKY_OSD = (1 << 20), // 1048576 + FUNCTION_DJI_HD_OSD = (1 << 21), // 2097152 } serialPortFunction_e; typedef enum { diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 1434ed1a828..b57c3a4c755 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -40,7 +40,7 @@ static mspPort_t mspPorts[MAX_MSP_PORT_COUNT]; -static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort) +void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort) { memset(mspPortToReset, 0, sizeof(mspPort_t)); @@ -452,6 +452,40 @@ static void mspProcessPendingRequest(mspPort_t * mspPort) } } +void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn) +{ + mspPostProcessFnPtr mspPostProcessFn = NULL; + + if (serialRxBytesWaiting(mspPort->port)) { + // There are bytes incoming - abort pending request + mspPort->lastActivityMs = millis(); + mspPort->pendingRequest = MSP_PENDING_NONE; + + // Process incoming bytes + while (serialRxBytesWaiting(mspPort->port)) { + const uint8_t c = serialRead(mspPort->port); + const bool consumed = mspSerialProcessReceivedData(mspPort, c); + + if (!consumed && evaluateNonMspData == MSP_EVALUATE_NON_MSP_DATA) { + mspEvaluateNonMspData(mspPort, c); + } + + if (mspPort->c_state == MSP_COMMAND_RECEIVED) { + mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn); + break; // process one command at a time so as not to block. + } + } + + if (mspPostProcessFn) { + waitForSerialPortToFinishTransmitting(mspPort->port); + mspPostProcessFn(mspPort->port); + } + } + else { + mspProcessPendingRequest(mspPort); + } +} + /* * Process MSP commands from serial ports configured as MSP ports. * @@ -461,39 +495,8 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm { for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) { mspPort_t * const mspPort = &mspPorts[portIndex]; - if (!mspPort->port) { - continue; - } - - mspPostProcessFnPtr mspPostProcessFn = NULL; - - if (serialRxBytesWaiting(mspPort->port)) { - // There are bytes incoming - abort pending request - mspPort->lastActivityMs = millis(); - mspPort->pendingRequest = MSP_PENDING_NONE; - - // Process incoming bytes - while (serialRxBytesWaiting(mspPort->port)) { - const uint8_t c = serialRead(mspPort->port); - const bool consumed = mspSerialProcessReceivedData(mspPort, c); - - if (!consumed && evaluateNonMspData == MSP_EVALUATE_NON_MSP_DATA) { - mspEvaluateNonMspData(mspPort, c); - } - - if (mspPort->c_state == MSP_COMMAND_RECEIVED) { - mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn); - break; // process one command at a time so as not to block. - } - } - - if (mspPostProcessFn) { - waitForSerialPortToFinishTransmitting(mspPort->port); - mspPostProcessFn(mspPort->port); - } - } - else { - mspProcessPendingRequest(mspPort); + if (mspPort->port) { + mspSerialProcessOnePort(mspPort, evaluateNonMspData, mspProcessCommandFn); } } } diff --git a/src/main/msp/msp_serial.h b/src/main/msp/msp_serial.h index 536f737fcef..0c495096808 100644 --- a/src/main/msp/msp_serial.h +++ b/src/main/msp/msp_serial.h @@ -18,6 +18,7 @@ #pragma once #include "drivers/time.h" +#include "io/serial.h" #include "msp/msp.h" // Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports. @@ -99,7 +100,9 @@ typedef struct mspPort_s { void mspSerialInit(void); +void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort); void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn); +void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn); void mspSerialAllocatePorts(void); void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort); int mspSerialPushPort(uint16_t cmd, const uint8_t *data, int datalen, mspPort_t *mspPort, mspVersion_e version); diff --git a/src/main/target/common.h b/src/main/target/common.h index c130c090917..5c8803245f3 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -107,6 +107,7 @@ #define USE_TELEMETRY_SIM #define USE_FRSKYOSD +#define USE_DJI_HD_OSD #define NAV_NON_VOLATILE_WAYPOINT_CLI diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index 0f5345cda3f..ffb333c72af 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -128,9 +128,9 @@ static ibusAddress_t getAddress(uint8_t ibusPacket[static IBUS_MIN_LEN]) { return (ibusPacket[1] & 0x0F); } -// MANUAL, ACRO, ANGLE, HRZN, ALTHOLD, POSHOLD, RTH, WP, LAUNCH, FAILSAFE -static uint8_t flightModeToIBusTelemetryMode1[FLM_COUNT] = { 0, 1, 3, 2, 5, 6, 7, 4, 8, 9 }; -static uint8_t flightModeToIBusTelemetryMode2[FLM_COUNT] = { 5, 1, 0, 7, 2, 8, 6, 3, 4, 9 }; +// MANUAL, ACRO, AIR, ANGLE, HRZN, ALTHOLD, POSHOLD, RTH, WP, CRUISE, LAUNCH, FAILSAFE +static uint8_t flightModeToIBusTelemetryMode1[FLM_COUNT] = { 0, 1, 1, 3, 2, 5, 6, 7, 4, 4, 8, 9 }; +static uint8_t flightModeToIBusTelemetryMode2[FLM_COUNT] = { 5, 1, 1, 0, 7, 2, 8, 6, 3, 3, 4, 9 }; static uint8_t dispatchMeasurementRequest(ibusAddress_t address) { #if defined(USE_GPS) uint8_t fix = 0; diff --git a/src/main/telemetry/sim.c b/src/main/telemetry/sim.c index c3b935af893..8fe6b7c53c5 100644 --- a/src/main/telemetry/sim.c +++ b/src/main/telemetry/sim.c @@ -132,7 +132,7 @@ static uint8_t simModuleState = SIM_MODULE_NOT_DETECTED; static int simRssi; static uint8_t accEvent = ACC_EVENT_NONE; static char* accEventDescriptions[] = { "", "HIT! ", "DROP ", "HIT " }; -static char* modeDescriptions[] = { "MAN", "ACR", "ANG", "HOR", "ALH", "POS", "RTH", "WP", "LAU", "FS" }; +static char* modeDescriptions[] = { "MAN", "ACR", "AIR", "ANG", "HOR", "ALH", "POS", "RTH", "WP", "CRS", "LAU", "FS" }; static const char gpsFixIndicators[] = { '!', '*', ' ' }; From 1a19a0498da20afbd2b95e4df8c3bcf324c5fff2 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 31 Dec 2019 22:55:28 +0100 Subject: [PATCH 083/110] [DJI] SBUS Fast protocol --- src/main/fc/settings.yaml | 2 +- src/main/rx/rx.c | 3 +++ src/main/rx/rx.h | 1 + src/main/rx/sbus.c | 17 ++++++++++++++--- src/main/rx/sbus.h | 1 + 5 files changed, 20 insertions(+), 4 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 189716b1859..4d4a8e6d00b 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -25,7 +25,7 @@ tables: values: ["NONE", "PWM", "PPM", "SERIAL", "MSP", "SPI", "UIB"] enum: rxReceiverType_e - name: serial_rx - values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT"] + values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST"] - name: rx_spi_protocol values: ["V202_250K", "V202_1M", "SYMA_X", "SYMA_X5C", "CX10", "CX10A", "H8_3D", "INAV", "ELERES"] enum: rx_spi_protocol_e diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 7ba4884c9c5..7628810a2eb 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -195,6 +195,9 @@ bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig case SERIALRX_SBUS: enabled = sbusInit(rxConfig, rxRuntimeConfig); break; + case SERIALRX_SBUS_FAST: + enabled = sbusInitFast(rxConfig, rxRuntimeConfig); + break; #endif #ifdef USE_SERIALRX_SUMD case SERIALRX_SUMD: diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 3d44a152e0b..1c35447fa71 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -79,6 +79,7 @@ typedef enum { SERIALRX_JETIEXBUS = 8, SERIALRX_CRSF = 9, SERIALRX_FPORT = 10, + SERIALRX_SBUS_FAST = 11, } rxSerialReceiverType_e; #define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 16 diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index d891b3539ba..04bc8556979 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -56,7 +56,8 @@ #define SBUS_FRAME_BEGIN_BYTE 0x0F -#define SBUS_BAUDRATE 100000 +#define SBUS_BAUDRATE 100000 +#define SBUS_BAUDRATE_FAST 200000 #if !defined(SBUS_PORT_OPTIONS) #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN) @@ -191,7 +192,7 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) return retValue; } -bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint32_t sbusBaudRate) { static uint16_t sbusChannelData[SBUS_MAX_CHANNEL]; static sbusFrameData_t sbusFrameData; @@ -221,7 +222,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) FUNCTION_RX_SERIAL, sbusDataReceive, &sbusFrameData, - SBUS_BAUDRATE, + sbusBaudRate, portShared ? MODE_RXTX : MODE_RX, SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); @@ -234,4 +235,14 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) return sBusPort != NULL; } + +bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE); +} + +bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST); +} #endif diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index b12a030f287..1fcd3680d0e 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -20,3 +20,4 @@ #define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); +bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); From db1ebaee5a5ad08e5ae67a16cb498dec0568e080 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 1 Jan 2020 13:36:13 +0100 Subject: [PATCH 084/110] [DJI] Fix broken F3 builds --- src/main/io/osd_dji_hd.c | 5 ++++- src/main/io/osd_dji_hd.h | 2 +- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 0f9e2573553..cd7447d8031 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -66,6 +66,7 @@ #include "scheduler/scheduler.h" +#if defined(USE_DJI_HD_OSD) #define DJI_MSP_BAUDRATE 115200 @@ -551,4 +552,6 @@ void djiOsdSerialProcess(void) // Piggyback on existing MSP protocol stack, but pass our special command processing function mspSerialProcessOnePort(&djiMspPort, MSP_SKIP_NON_MSP_DATA, djiProcessMspCommand); -} \ No newline at end of file +} + +#endif diff --git a/src/main/io/osd_dji_hd.h b/src/main/io/osd_dji_hd.h index 97dddf9857b..2db5fd362e5 100644 --- a/src/main/io/osd_dji_hd.h +++ b/src/main/io/osd_dji_hd.h @@ -59,4 +59,4 @@ void djiOsdSerialInit(void); void djiOsdSerialProcess(void); -#endif \ No newline at end of file +#endif From fae65779163703c28cf61bc1483fee02b1365520 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 2 Jan 2020 18:21:48 +0100 Subject: [PATCH 085/110] [DJI] Fix missing arming status --- src/main/io/osd_dji_hd.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index cd7447d8031..24281b4e86b 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -206,6 +206,7 @@ static void djiPackBoxModeBitmask(boxBitmask_t * flightModeBitmask) { memset(flightModeBitmask, 0, sizeof(boxBitmask_t)); + // Map flight modes to DJI-supported bits switch(getFlightModeForTelemetry()) { case FLM_MANUAL: case FLM_ACRO: @@ -235,6 +236,11 @@ static void djiPackBoxModeBitmask(boxBitmask_t * flightModeBitmask) // Unsupported ATM, keep at ANGLE bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE } + + // Set ARMED mode + if (ARMING_FLAG(ARMED)) { + bitArraySet(flightModeBitmask->bits, 0); // DJI: 1 << 0 : ARMED + } } static uint32_t djiPackArmingDisabledFlags(void) From d3cc8fb5662ee077a5ec28045142c1fbbbd04876 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 4 Jan 2020 12:30:34 +0000 Subject: [PATCH 086/110] [GF/LF] Fix PG resets for global functions and logic functions - globalFunction_t needs to be registered with a reset fn, otherwise it's never called. - logicCondition_t is reset to all zeroes, so it doesn't need a reset fn at all, it can be just deleted. --- src/main/common/global_functions.c | 4 ++-- src/main/common/logic_condition.c | 21 +-------------------- 2 files changed, 3 insertions(+), 22 deletions(-) diff --git a/src/main/common/global_functions.c b/src/main/common/global_functions.c index 7bf44669130..7421dab33cc 100644 --- a/src/main/common/global_functions.c +++ b/src/main/common/global_functions.c @@ -38,7 +38,7 @@ #include "common/axis.h" -PG_REGISTER_ARRAY(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0); +PG_REGISTER_ARRAY_WITH_RESET_FN(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0); EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0; EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS]; @@ -164,4 +164,4 @@ int16_t FAST_CODE getRcCommandOverride(int16_t command[], uint8_t axis) { return outputValue; } -#endif \ No newline at end of file +#endif diff --git a/src/main/common/logic_condition.c b/src/main/common/logic_condition.c index 9f1be2ce0c4..14d6cadcaa6 100644 --- a/src/main/common/logic_condition.c +++ b/src/main/common/logic_condition.c @@ -42,25 +42,6 @@ PG_REGISTER_ARRAY(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 0); -void pgResetFn_logicConditions(logicCondition_t *instance) -{ - for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { - RESET_CONFIG(logicCondition_t, &instance[i], - .enabled = 0, - .operation = LOGIC_CONDITION_TRUE, - .operandA = { - .type = LOGIC_CONDITION_OPERAND_TYPE_VALUE, - .value = 0 - }, - .operandB = { - .type = LOGIC_CONDITION_OPERAND_TYPE_VALUE, - .value = 0 - }, - .flags = 0 - ); - } -} - logicConditionState_t logicConditionStates[MAX_LOGIC_CONDITIONS]; static int logicConditionCompute( @@ -363,4 +344,4 @@ void logicConditionReset(void) { logicConditionStates[i].value = 0; logicConditionStates[i].flags = 0; } -} \ No newline at end of file +} From 9f0923ab2ce3afe8021e30058d2948801b6fa341 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 4 Jan 2020 16:11:53 +0000 Subject: [PATCH 087/110] document nav_wp_safe_distance == 0 over-ride --- docs/Cli.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Cli.md b/docs/Cli.md index 64799baab90..fb089c468be 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -182,7 +182,7 @@ A shorter form is also supported to enable and disable functions using `serial < | nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | | nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | | nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm] | +| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | | nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | | nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | | nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | From 8f5f6ef91e741ce66167b74a5f861286537a96d8 Mon Sep 17 00:00:00 2001 From: Fabian Schwartau Date: Tue, 7 Jan 2020 20:01:35 +0100 Subject: [PATCH 088/110] Fixed inverted axis in MAG3110 according to datasheet --- src/main/drivers/compass/compass_mag3110.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/compass/compass_mag3110.c b/src/main/drivers/compass/compass_mag3110.c index 4abc44ca04e..5cd8454ebc8 100755 --- a/src/main/drivers/compass/compass_mag3110.c +++ b/src/main/drivers/compass/compass_mag3110.c @@ -97,7 +97,7 @@ static bool mag3110Read(magDev_t * mag) mag->magADCRaw[X] = (int16_t)(buf[0] << 8 | buf[1]); mag->magADCRaw[Y] = (int16_t)(buf[2] << 8 | buf[3]); - mag->magADCRaw[Z] = (int16_t)(buf[4] << 8 | buf[5]); + mag->magADCRaw[Z] = -(int16_t)(buf[4] << 8 | buf[5]); // Z is down, not up in this sensor return true; } From 149fd54aa37b33efaaa0e73ef0b8ebf4c5c615ae Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sun, 12 Jan 2020 10:20:27 +0100 Subject: [PATCH 089/110] [DJI] Support setting PIDs via DJI HD goggles --- src/main/io/osd_dji_hd.c | 74 ++++++++++++++++++++++++++++++++++++++-- src/main/io/osd_dji_hd.h | 4 +++ 2 files changed, 75 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 24281b4e86b..bc44c631eda 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -41,6 +41,7 @@ #include "fc/fc_core.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" #include "fc/fc_msp.h" #include "fc/fc_msp_box.h" #include "fc/runtime_config.h" @@ -57,6 +58,9 @@ #include "sensors/sensors.h" #include "sensors/battery.h" +#include "sensors/rangefinder.h" +#include "sensors/acceleration.h" +#include "sensors/gyro.h" #include "msp/msp.h" #include "msp/msp_protocol.h" @@ -364,7 +368,7 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms UNUSED(mspPostProcessFn); sbuf_t *dst = &reply->buf; - //sbuf_t *src = &cmd->buf; + sbuf_t *src = &cmd->buf; // Start initializing the reply message reply->cmd = cmd->cmd; @@ -527,10 +531,74 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms break; case DJI_MSP_FILTER_CONFIG: - case DJI_MSP_PID_ADVANCED: + sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz); // BF: gyroConfig()->gyro_lowpass_hz + sbufWriteU16(dst, pidProfile()->dterm_lpf_hz); // BF: currentPidProfile->dterm_lowpass_hz + sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); // BF: currentPidProfile->yaw_lowpass_hz + sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); // BF: gyroConfig()->gyro_soft_notch_hz_1 + sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); // BF: gyroConfig()->gyro_soft_notch_cutoff_1 + sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); // BF: currentPidProfile->dterm_notch_hz + sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); // BF: currentPidProfile->dterm_notch_cutoff + sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_2); // BF: gyroConfig()->gyro_soft_notch_hz_2 + sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_2); // BF: gyroConfig()->gyro_soft_notch_cutoff_2 + sbufWriteU8(dst, 0); // BF: currentPidProfile->dterm_filter_type + sbufWriteU8(dst, gyroConfig()->gyro_lpf); // BF: gyroConfig()->gyro_hardware_lpf); + sbufWriteU8(dst, 0); // BF: DEPRECATED: gyro_32khz_hardware_lpf + sbufWriteU16(dst, gyroConfig()->gyro_soft_lpf_hz); // BF: gyroConfig()->gyro_lowpass_hz); + sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz); // BF: gyroConfig()->gyro_lowpass2_hz); + sbufWriteU8(dst, 0); // BF: gyroConfig()->gyro_lowpass_type); + sbufWriteU8(dst, 0); // BF: gyroConfig()->gyro_lowpass2_type); + sbufWriteU16(dst, 0); // BF: currentPidProfile->dterm_lowpass2_hz); + sbufWriteU8(dst, 0); // BF: currentPidProfile->dterm_filter2_type); + break; + case DJI_MSP_RC_TUNING: + sbufWriteU8(dst, 100); // INAV doesn't use rcRate + sbufWriteU8(dst, currentControlRateProfile->stabilized.rcExpo8); + for (int i = 0 ; i < 3; i++) { + // R,P,Y rates see flight_dynamics_index_t + sbufWriteU8(dst, currentControlRateProfile->stabilized.rates[i]); + } + sbufWriteU8(dst, currentControlRateProfile->throttle.dynPID); + sbufWriteU8(dst, currentControlRateProfile->throttle.rcMid8); + sbufWriteU8(dst, currentControlRateProfile->throttle.rcExpo8); + sbufWriteU16(dst, currentControlRateProfile->throttle.pa_breakpoint); + sbufWriteU8(dst, currentControlRateProfile->stabilized.rcYawExpo8); + sbufWriteU8(dst, 100); // INAV doesn't use rcRate + sbufWriteU8(dst, 100); // INAV doesn't use rcRate + sbufWriteU8(dst, currentControlRateProfile->stabilized.rcExpo8); + + // added in 1.41 + sbufWriteU8(dst, 0); + sbufWriteU8(dst, currentControlRateProfile->throttle.dynPID); + break; + case DJI_MSP_ESC_SENSOR_DATA: - // TODO + case DJI_MSP_PID_ADVANCED: + reply->result = MSP_RESULT_ERROR; + break; + + case DJI_MSP_SET_PID: + // Check if we have enough data for all PID coefficients + if ((unsigned)sbufBytesRemaining(src) >= ARRAYLEN(djiPidIndexMap) * 3) { + for (unsigned i = 0; i < ARRAYLEN(djiPidIndexMap); i++) { + pidBankMutable()->pid[djiPidIndexMap[i]].P = sbufReadU8(src); + pidBankMutable()->pid[djiPidIndexMap[i]].I = sbufReadU8(src); + pidBankMutable()->pid[djiPidIndexMap[i]].D = sbufReadU8(src); + } + schedulePidGainsUpdate(); +#if defined(USE_NAV) + // This is currently unnecessary, DJI HD doesn't set any NAV PIDs + //navigationUsePIDs(); +#endif + } + else { + reply->result = MSP_RESULT_ERROR; + } + break; + + case DJI_MSP_SET_FILTER_CONFIG: + case DJI_MSP_SET_PID_ADVANCED: + case DJI_MSP_SET_RC_TUNING: reply->result = MSP_RESULT_ERROR; break; diff --git a/src/main/io/osd_dji_hd.h b/src/main/io/osd_dji_hd.h index 2db5fd362e5..d1105783d31 100644 --- a/src/main/io/osd_dji_hd.h +++ b/src/main/io/osd_dji_hd.h @@ -55,6 +55,10 @@ #define DJI_MSP_STATUS_EX 150 // INAV: Implemented | DSI: Implemented | For OSD ‘Fly mode', For OSD ‘Disarmed’ #define DJI_MSP_RTC 247 // INAV: Implemented | DSI: Implemented | For OSD ‘RTC date time’ +#define DJI_MSP_SET_FILTER_CONFIG 93 +#define DJI_MSP_SET_PID_ADVANCED 95 +#define DJI_MSP_SET_PID 202 +#define DJI_MSP_SET_RC_TUNING 204 void djiOsdSerialInit(void); void djiOsdSerialProcess(void); From b9ea66eb9d9001da307522e996cc866ac7a838fa Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sun, 12 Jan 2020 10:29:17 +0100 Subject: [PATCH 090/110] [DJI] Add ESC telemetry support --- src/main/io/osd_dji_hd.c | 35 +++++++++++++++++++++++++++-------- src/main/sensors/esc_sensor.c | 4 ++-- 2 files changed, 29 insertions(+), 10 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index bc44c631eda..a6a0f46f72f 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -48,6 +48,7 @@ #include "flight/imu.h" #include "flight/pid.h" +#include "flight/mixer.h" #include "io/serial.h" #include "io/gps.h" @@ -57,10 +58,11 @@ #include "rx/rx.h" #include "sensors/sensors.h" +#include "sensors/gyro.h" #include "sensors/battery.h" #include "sensors/rangefinder.h" #include "sensors/acceleration.h" -#include "sensors/gyro.h" +#include "sensors/esc_sensor.h" #include "msp/msp.h" #include "msp/msp_protocol.h" @@ -521,6 +523,22 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms } break; +#if defined(USE_ESC_SENSOR) + case DJI_MSP_ESC_SENSOR_DATA: + if (STATE(ESC_SENSOR_ENABLED)) { + sbufWriteU8(dst, getMotorCount()); + for (int i = 0; i < getMotorCount(); i++) { + const escSensorData_t * escSensor = getEscTelemetry(i); + sbufWriteU8(dst, escSensor->temperature); + sbufWriteU16(dst, escSensor->rpm); + } + } + else { + reply->result = MSP_RESULT_ERROR; + } + break; +#endif + case DJI_MSP_OSD_CONFIG: #if defined(USE_OSD) // This involved some serious magic, better contain in a separate function for readability @@ -572,11 +590,6 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU8(dst, currentControlRateProfile->throttle.dynPID); break; - case DJI_MSP_ESC_SENSOR_DATA: - case DJI_MSP_PID_ADVANCED: - reply->result = MSP_RESULT_ERROR; - break; - case DJI_MSP_SET_PID: // Check if we have enough data for all PID coefficients if ((unsigned)sbufBytesRemaining(src) >= ARRAYLEN(djiPidIndexMap) * 3) { @@ -596,15 +609,21 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms } break; + case DJI_MSP_PID_ADVANCED: + // TODO + reply->result = MSP_RESULT_ERROR; + break; + case DJI_MSP_SET_FILTER_CONFIG: case DJI_MSP_SET_PID_ADVANCED: case DJI_MSP_SET_RC_TUNING: + // TODO reply->result = MSP_RESULT_ERROR; break; default: - debug[1]++; - debug[2] = cmd->cmd; + // debug[1]++; + // debug[2] = cmd->cmd; reply->result = MSP_RESULT_ERROR; break; } diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c index 97437315815..618db672212 100644 --- a/src/main/sensors/esc_sensor.c +++ b/src/main/sensors/esc_sensor.c @@ -112,7 +112,7 @@ static bool escSensorDecodeFrame(void) escSensorData[escSensorMotor].temperature = telemetryBuffer[0]; escSensorData[escSensorMotor].voltage = ((uint16_t)telemetryBuffer[1]) << 8 | telemetryBuffer[2]; escSensorData[escSensorMotor].current = ((uint16_t)telemetryBuffer[3]) << 8 | telemetryBuffer[4]; - escSensorData[escSensorMotor].rpm = ((uint16_t)telemetryBuffer[7]) << 8 | telemetryBuffer[8]; + escSensorData[escSensorMotor].rpm = computeRpm(((uint16_t)telemetryBuffer[7]) << 8 | telemetryBuffer[8]); escSensorDataNeedsUpdate = true; if (escSensorMotor < 4) { @@ -169,7 +169,7 @@ escSensorData_t * escSensorGetData(void) if (usedEscSensorCount) { escSensorDataCombined.current = (uint32_t)escSensorDataCombined.current * getMotorCount() / usedEscSensorCount + escSensorConfig()->currentOffset; escSensorDataCombined.voltage = (uint32_t)escSensorDataCombined.voltage / usedEscSensorCount; - escSensorDataCombined.rpm = computeRpm((float)escSensorDataCombined.rpm / usedEscSensorCount); + escSensorDataCombined.rpm = (float)escSensorDataCombined.rpm / usedEscSensorCount; } else { escSensorDataCombined.dataAge = ESC_DATA_INVALID; From 96c68363a9c04467b2c0573777cf5e3214214beb Mon Sep 17 00:00:00 2001 From: Mark Hale Date: Wed, 8 Jan 2020 00:00:52 +0000 Subject: [PATCH 091/110] Disable servo output while using CMS. --- src/main/cms/cms.c | 4 ++++ src/main/flight/servos.c | 5 +++++ src/main/flight/servos.h | 1 + 3 files changed, 10 insertions(+) diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 6d70284c9d1..fcfb56ebeae 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -63,6 +63,7 @@ #include "fc/settings.h" #include "flight/mixer.h" +#include "flight/servos.h" // For VISIBLE* #include "io/osd.h" @@ -765,6 +766,7 @@ void cmsMenuOpen(void) { if (!cmsInMenu) { // New open + setServoOutputEnabled(false); pCurrentDisplay = cmsDisplayPortSelectCurrent(); if (!pCurrentDisplay) return; @@ -860,6 +862,8 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) displayRelease(pDisplay); currentCtx.menu = NULL; + setServoOutputEnabled(true); + if ((exitType == CMS_EXIT_SAVEREBOOT) || (exitType == CMS_POPUP_SAVEREBOOT)) { displayClearScreen(pDisplay); displayWrite(pDisplay, 5, 3, "REBOOTING..."); diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 8ecc5f3200a..3ddf770afe0 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -449,6 +449,11 @@ bool FAST_CODE NOINLINE isServoOutputEnabled(void) return servoOutputEnabled; } +void NOINLINE setServoOutputEnabled(bool flag) +{ + servoOutputEnabled = flag; +} + bool FAST_CODE NOINLINE isMixerUsingServos(void) { return mixerUsesServos; diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 7d8a2d3ca15..555962defe3 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -143,6 +143,7 @@ typedef struct servoMetadata_s { extern int16_t servo[MAX_SUPPORTED_SERVOS]; bool isServoOutputEnabled(void); +void setServoOutputEnabled(bool flag); bool isMixerUsingServos(void); void writeServos(void); void loadCustomServoMixer(void); From 5f5220956d73373fde186a25dfc089f61fa8cc70 Mon Sep 17 00:00:00 2001 From: azolyoung Date: Mon, 13 Jan 2020 17:46:48 +0800 Subject: [PATCH 092/110] fixes servo not work on speedybeef4 --- src/main/target/SPEEDYBEEF4/target.c | 15 ++++++++------- src/main/target/SPEEDYBEEF4/target.h | 4 ++-- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/main/target/SPEEDYBEEF4/target.c b/src/main/target/SPEEDYBEEF4/target.c index 3c5b3162c8a..45a98da28b3 100644 --- a/src/main/target/SPEEDYBEEF4/target.c +++ b/src/main/target/SPEEDYBEEF4/target.c @@ -24,17 +24,18 @@ #include "drivers/bus.h" const timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP(1,2) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 UP(2,1) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP(2,1) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP(2,1) - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP(1,2) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 UP(2,1) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 UP(2,1) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP(2,1) DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 UP(1,7) DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 UP(2,5) - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D(1,0) UP(2,6) + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D(1,0) UP(2,6) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF4/target.h b/src/main/target/SPEEDYBEEF4/target.h index 96ce695a5c8..0e7f8e2c539 100644 --- a/src/main/target/SPEEDYBEEF4/target.h +++ b/src/main/target/SPEEDYBEEF4/target.h @@ -150,8 +150,8 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE // Number of available PWM outputs -#define MAX_PWM_OUTPUT_PORTS 6 -#define TARGET_MOTOR_COUNT 6 +#define MAX_PWM_OUTPUT_PORTS 7 +#define TARGET_MOTOR_COUNT 7 #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff From 44c986736964966bee1a3fa7835ad3299d011cc1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 15 Jan 2020 10:36:37 +0000 Subject: [PATCH 093/110] [BUILD] Fix build with DEBUG=GDB and semihosting enabled Kudos to @shellixyz for spotting it --- Makefile | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 1b015d486ae..f19b1b09381 100644 --- a/Makefile +++ b/Makefile @@ -185,9 +185,11 @@ endif ifneq ($(SEMIHOSTING),) SEMIHOSTING_CFLAGS = -DSEMIHOSTING SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon +SYSLIB := else SEMIHOSTING_CFLAGS = SEMIHOSTING_LDFLAGS = +SYSLIB := -lnosys endif DEBUG_FLAGS = -ggdb3 -DDEBUG @@ -224,7 +226,7 @@ LDFLAGS = -lm \ -nostartfiles \ --specs=nano.specs \ -lc \ - -lnosys \ + $(SYSLIB) \ $(ARCH_FLAGS) \ $(LTO_FLAGS) \ $(DEBUG_FLAGS) \ From b9b79eab9b878bab0ce81fac1fb577d6a888148a Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sat, 18 Jan 2020 15:35:05 +0100 Subject: [PATCH 094/110] Add missing ESC RPM OSD item to OSD menu --- src/main/cms/cms_menu_osd.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 5ba507addde..d902acb26b5 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -271,6 +271,10 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("SENSOR 7 TEMP", OSD_TEMP_SENSOR_7_TEMPERATURE), #endif +#ifdef USE_ESC_SENSOR + OSD_ELEMENT_ENTRY("ESC RPM", OSD_ESC_RPM), +#endif + OSD_BACK_AND_END_ENTRY, }; From 608d08cfef6c6a053deacc458f0e68107db84d5b Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sat, 18 Jan 2020 15:37:51 +0100 Subject: [PATCH 095/110] Add ICM20601 IMU support (#5333) --- src/main/drivers/accgyro/accgyro_mpu6500.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c index ca8bb993d92..532fd036066 100755 --- a/src/main/drivers/accgyro/accgyro_mpu6500.c +++ b/src/main/drivers/accgyro/accgyro_mpu6500.c @@ -127,6 +127,7 @@ static bool mpu6500DeviceDetect(busDevice_t * dev) switch (tmp) { case MPU6500_WHO_AM_I_CONST: case ICM20608G_WHO_AM_I_CONST: + case ICM20601_WHO_AM_I_CONST: case ICM20602_WHO_AM_I_CONST: case ICM20689_WHO_AM_I_CONST: // Compatible chip detected From 1727a17340054111e6bbc5d17869c4475bc38f6b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 22 Jan 2020 20:45:42 +0000 Subject: [PATCH 096/110] [CANVAS] Fix home direction arrow orientation Arrow as rotating in the correct direction, but it was drawn inverted 180 degrees (i.e. it pointed up when it should point down). Kudos to @fmartinezo for the heads up --- src/main/io/osd_canvas.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 5a4c310a353..c4d562be456 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -116,7 +116,7 @@ void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, cons displayCanvasSetFillColor(canvas, DISPLAY_CANVAS_COLOR_WHITE); displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); - displayCanvasCtmRotate(canvas, -DEGREES_TO_RADIANS(degrees)); + displayCanvasCtmRotate(canvas, -DEGREES_TO_RADIANS(180 + degrees)); displayCanvasCtmTranslate(canvas, px + canvas->gridElementWidth / 2, py + canvas->gridElementHeight / 2); displayCanvasFillStrokeTriangle(canvas, 0, 6, 5, -6, -5, -6); displayCanvasSetFillColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); From 088d9523eeb69be95089dacff477fc92a0d90dce Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 23 Jan 2020 20:31:53 +0100 Subject: [PATCH 097/110] Update Cli.md with new settings --- docs/Cli.md | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index fb089c468be..802a00a341b 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -290,7 +290,6 @@ A shorter form is also supported to enable and disable functions using `serial < | pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | | alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | | yaw_motor_direction | 1 | Use if you need to inverse yaw motor direction. | -| yaw_jump_prevention_limit | 200 | Prevent yaw jumps during yaw stops and rapid YAW input. To disable set to 500. Adjust this if your aircraft 'skids out'. Higher values increases YAW authority but can cause roll/pitch instability in case of underpowered UAVs. Lower values makes yaw adjustments more gentle but can cause UAV unable to keep heading | | tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. | | servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | | servo_center_pulse | 1500 | Servo midpoint | @@ -420,14 +419,27 @@ A shorter form is also supported to enable and disable functions using `serial < | acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | | acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | | dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value | +| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | +| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | | yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | | dyn_notch_width_percent | 8 | Distance in % of the attenuated frequency for double dynamic filter notched. When set to `0` single dynamic notch filter is used | | dyn_notch_range | MEDIUM | Dynamic gyro filter range. Possible values `LOW` `MEDIUM` `HIGH`. `MEDIUM` should work best for 5-6" multirotors. `LOW` should work best with 7" and bigger. `HIGH` should work with everything below 4" | | dyn_notch_q | 120 | Q factor for dynamic notches | | dyn_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | -| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz). Currently experimental | +| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | +| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | +| rpm_dterm_filter_enabled | `OFF` | RPM filter for D-term. Experimental, probably will be removed in the next release | +| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | +| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` | +| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | +| dterm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by D-term RPM filter. Default value of `1` usually works just fine | +| rpm_dterm_min_hz | 150 | - | +| rpm_dterm_q | 500 | - | | pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| `pid_type` | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | | iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | | rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | | rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | From bd3a1a091d656348bbd3fff9f15358bfe41caf6b Mon Sep 17 00:00:00 2001 From: Ben Smith Date: Sat, 25 Jan 2020 14:44:09 -0500 Subject: [PATCH 098/110] fixed craft name spaces bug --- src/main/io/osd_dji_hd.c | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index a6a0f46f72f..60cea611d01 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -397,10 +397,13 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms break; case DJI_MSP_NAME: - for (const char * name = systemConfig()->name; *name; name++) { - sbufWriteU8(dst, *name++); - } - break; + { + const char * name = systemConfig()->name; + int len = strlen(name); + if (len > 12) len = 12; + sbufWriteData(dst, name, len); + } + break; case DJI_MSP_STATUS: case DJI_MSP_STATUS_EX: From 5b6443ac0078bf6088b546999612d81f8f1606da Mon Sep 17 00:00:00 2001 From: Alvaro Calvo Date: Mon, 27 Jan 2020 13:13:59 -0500 Subject: [PATCH 099/110] Enabled led strip support to Kakute F7 flight controller --- src/main/target/KAKUTEF7/target.c | 2 +- src/main/target/KAKUTEF7/target.h | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/main/target/KAKUTEF7/target.c b/src/main/target/KAKUTEF7/target.c index 17cbd1df6d0..1ba0c8c035d 100755 --- a/src/main/target/KAKUTEF7/target.c +++ b/src/main/target/KAKUTEF7/target.c @@ -38,7 +38,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7 DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_TRIP, DMA1_ST0 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 01984ed350a..82be9590a0a 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -172,6 +172,9 @@ #define SERIALRX_UART SERIAL_PORT_USART6 #define SERIALRX_PROVIDER SERIALRX_SBUS +#define USE_LED_STRIP +#define WS2811_PIN PD12 //TIM4_CH1 + #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff From c00e914fab026446b7ce8d52d73acba1560e02c6 Mon Sep 17 00:00:00 2001 From: jingxian-xiao Date: Tue, 28 Jan 2020 18:08:15 +0800 Subject: [PATCH 100/110] F4BY add ICM-20689 driver --- src/main/target/F4BY/target.h | 9 +++++++++ src/main/target/F4BY/target.mk | 1 + 2 files changed, 10 insertions(+) diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index bcdf88a1e8a..9231b8a8088 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -35,6 +35,9 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +#define ICM20689_CS_PIN PA4 +#define ICM20689_SPI_BUS BUS_SPI1 + #define USE_ACC #define USE_ACC_MPU6000 @@ -44,6 +47,12 @@ #define USE_GYRO_MPU6000 #define GYRO_MPU6000_ALIGN CW90_DEG +#define USE_ACC_ICM20689 +#define ACC_ICM20689_ALIGN CW90_DEG + +#define USE_GYRO_ICM20689 +#define GYRO_ICM20689_ALIGN CW90_DEG + #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 #define MAG_HMC5883_ALIGN CW90_DEG diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk index e5221e515ea..774e7e730a6 100644 --- a/src/main/target/F4BY/target.mk +++ b/src/main/target/F4BY/target.mk @@ -3,6 +3,7 @@ FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ + drivers/accgyro/accgyro_icm20689.c \ drivers/barometer/barometer_ms56xx.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ From b6d143c055d8c3ce927e1c13b70fbb580639b180 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 28 Jan 2020 21:32:25 +0000 Subject: [PATCH 101/110] [MSP] Add support for setting up serial passthrough via MSP Change MSP_SET_4WAY_IF to MSP_SET_PASSTHROUGH while also keeping backwards compatibility. --- src/main/fc/fc_msp.c | 78 +++++++++++++++++++++++++++++-------- src/main/msp/msp_protocol.h | 2 +- 2 files changed, 62 insertions(+), 18 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 014f0a5ddc5..8adea1b05bb 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -153,26 +153,74 @@ typedef enum { MSP_FLASHFS_BIT_SUPPORTED = 2 } mspFlashfsFlags_e; -#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE -#define ESC_4WAY 0xff +typedef enum { + MSP_PASSTHROUGH_SERIAL_ID = 0xFD, + MSP_PASSTHROUGH_SERIAL_FUNCTION_ID = 0xFE, + + MSP_PASSTHROUGH_ESC_4WAY = 0xFF, + } mspPassthroughType_e; + +static uint8_t mspPassthroughMode; +static uint8_t mspPassthroughArgument; + +static serialPort_t *mspFindPassthroughSerialPort(void) + { + serialPortUsage_t *portUsage = NULL; + + switch (mspPassthroughMode) { + case MSP_PASSTHROUGH_SERIAL_ID: + { + portUsage = findSerialPortUsageByIdentifier(mspPassthroughArgument); + break; + } + case MSP_PASSTHROUGH_SERIAL_FUNCTION_ID: + { + const serialPortConfig_t *portConfig = findSerialPortConfig(1 << mspPassthroughArgument); + if (portConfig) { + portUsage = findSerialPortUsageByIdentifier(portConfig->identifier); + } + break; + } + } + return portUsage ? portUsage->serialPort : NULL; +} -static uint8_t escMode; -static uint8_t escPortIndex; +static void mspSerialPassthroughFn(serialPort_t *serialPort) +{ + serialPort_t *passthroughPort = mspFindPassthroughSerialPort(); + if (passthroughPort && serialPort) { + serialPassthrough(passthroughPort, serialPort, NULL, NULL); + } +} -static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) +static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) { const unsigned int dataSize = sbufBytesRemaining(src); if (dataSize == 0) { // Legacy format - escMode = ESC_4WAY; + mspPassthroughMode = MSP_PASSTHROUGH_ESC_4WAY; } else { - escMode = sbufReadU8(src); - escPortIndex = sbufReadU8(src); + mspPassthroughMode = sbufReadU8(src); + if (!sbufReadU8Safe(&mspPassthroughArgument, src)) { + mspPassthroughArgument = 0; + } } - switch (escMode) { - case ESC_4WAY: + switch (mspPassthroughMode) { + case MSP_PASSTHROUGH_SERIAL_ID: + case MSP_PASSTHROUGH_SERIAL_FUNCTION_ID: + if (mspFindPassthroughSerialPort()) { + if (mspPostProcessFn) { + *mspPostProcessFn = mspSerialPassthroughFn; + } + sbufWriteU8(dst, 1); + } else { + sbufWriteU8(dst, 0); + } + break; +#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE + case MSP_PASSTHROUGH_ESC_4WAY: // get channel number // switch all motor lines HI // reply with the count of ESC found @@ -182,14 +230,12 @@ static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn = esc4wayProcess; } break; - +#endif default: sbufWriteU8(dst, 0); } } -#endif - static void mspRebootFn(serialPort_t *serialPort) { UNUSED(serialPort); @@ -3177,11 +3223,9 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro ret = mspProcessSensorCommand(cmdMSP, src); } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { ret = MSP_RESULT_ACK; -#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE - } else if (cmdMSP == MSP_SET_4WAY_IF) { - mspFc4waySerialCommand(dst, src, mspPostProcessFn); + } else if (cmdMSP == MSP_SET_PASSTHROUGH) { + mspFcSetPassthroughCommand(dst, src, mspPostProcessFn); ret = MSP_RESULT_ACK; -#endif } else { if (!mspFCProcessInOutCommand(cmdMSP, dst, src, &ret)) { ret = mspFcProcessInCommand(cmdMSP, src); diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index b1308d91920..dfa560b0a07 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -321,7 +321,7 @@ #define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values #define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration #define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration -#define MSP_SET_4WAY_IF 245 //in message Sets 4way interface +#define MSP_SET_PASSTHROUGH 245 //in message Sets up passthrough to different peripherals (4way interface, uart, etc...) #define MSP_RTC 246 //out message Gets the RTC clock (returns: secs(i32) millis(u16) - (0,0) if time is not known) #define MSP_SET_RTC 247 //in message Sets the RTC clock (args: secs(i32) millis(u16)) From 5af62240e5acfe1805eddf78dde1da4c9bef976d Mon Sep 17 00:00:00 2001 From: Ben Smith Date: Wed, 29 Jan 2020 11:54:25 -0500 Subject: [PATCH 102/110] fixed formatting --- src/main/io/osd_dji_hd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 60cea611d01..e72d474607a 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -402,8 +402,8 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms int len = strlen(name); if (len > 12) len = 12; sbufWriteData(dst, name, len); - } - break; + } + break; case DJI_MSP_STATUS: case DJI_MSP_STATUS_EX: From 00beb08ff503cf462691a7b250d7a352add7c6fa Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 29 Jan 2020 21:20:06 +0100 Subject: [PATCH 103/110] Fix indentation --- src/main/io/osd_dji_hd.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index e72d474607a..38e7bf52ce9 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -401,9 +401,9 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms const char * name = systemConfig()->name; int len = strlen(name); if (len > 12) len = 12; - sbufWriteData(dst, name, len); - } - break; + sbufWriteData(dst, name, len); + } + break; case DJI_MSP_STATUS: case DJI_MSP_STATUS_EX: From 2bf5f90a7c615e8519ff022b3f925d707fdc2f9a Mon Sep 17 00:00:00 2001 From: Konstantin Sharlaimov Date: Thu, 30 Jan 2020 16:13:31 +0100 Subject: [PATCH 104/110] Add MAMBAF722 and MAMBA405US to release targets Missed, apparently --- make/release.mk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/make/release.mk b/make/release.mk index cff7d397186..bc7c18e83eb 100644 --- a/make/release.mk +++ b/make/release.mk @@ -25,10 +25,10 @@ RELEASE_TARGETS += NOX WINGFC RELEASE_TARGETS += OMNIBUSF4V6 -RELEASE_TARGETS += MAMBAF405 +RELEASE_TARGETS += MAMBAF405 MAMBAF405US MAMBAF722 RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING RELEASE_TARGETS += AIKONF4 -RELEASE_TARGETS += MATEKF765 \ No newline at end of file +RELEASE_TARGETS += MATEKF765 From 3c0f092085af06336de38fc33d7e164eed1329be Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Fri, 31 Jan 2020 19:57:14 +0100 Subject: [PATCH 105/110] Fix a typo in MAMBA722S target definition --- src/main/target/MAMBAF722/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h index 63989ba97ce..09c30747567 100644 --- a/src/main/target/MAMBAF722/target.h +++ b/src/main/target/MAMBAF722/target.h @@ -46,7 +46,7 @@ #define USE_ACC #define USE_ACC_MPU6000 -#define ACC_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG // *************** Baro ************************** #define USE_I2C From e41bb7510355a5cb3d28cdc1e79b146cd73e1e2a Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sun, 2 Feb 2020 19:35:02 +0100 Subject: [PATCH 106/110] [RPM] Enlarge RPM data type to uint32_t to prevent overlow in computing average RPM --- src/main/sensors/esc_sensor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/sensors/esc_sensor.h b/src/main/sensors/esc_sensor.h index 1e10d834b4d..97d5671d425 100644 --- a/src/main/sensors/esc_sensor.h +++ b/src/main/sensors/esc_sensor.h @@ -29,7 +29,7 @@ typedef struct { int8_t temperature; int16_t voltage; int32_t current; - int16_t rpm; + uint32_t rpm; } escSensorData_t; typedef struct escSensorConfig_s { From aaa598263d4f6e8593545cf768e53830d61fba84 Mon Sep 17 00:00:00 2001 From: stronnag Date: Tue, 4 Feb 2020 07:11:22 +0000 Subject: [PATCH 107/110] [developer] document serial printf logging / debugging function (#5376) * add developer documentation for serial log / debug * minor clean up [skip ci] * remove ? around configurator [ci skip] * pointless commit so travis rebuilds the whole project --- docs/development/serial_printf_debugging.md | 125 ++++++++++++++++++++ 1 file changed, 125 insertions(+) create mode 100644 docs/development/serial_printf_debugging.md diff --git a/docs/development/serial_printf_debugging.md b/docs/development/serial_printf_debugging.md new file mode 100644 index 00000000000..a2912ea69d9 --- /dev/null +++ b/docs/development/serial_printf_debugging.md @@ -0,0 +1,125 @@ +# Serial printf style debugging + +## Overview + +iNav offers a function to use serial `printf` style debugging. + +This provides a simple and intuitive debugging facility. This facility is only available after the serial sub-system has been initialised, which should be adequate for all but the most hard-core debugging requirements. + +## CLI settings + +It is necessary to set a serial port for serial logging using the function mask `FUNCTION_LOG`, 32768. For convenience this may be shared with MSP (mask 1), but no other function. +For example, on a VCP port. + +``` +serial 20 32769 115200 115200 0 115200 +``` + +If the port is shared, it will be resused with extant settings; if the port is not shared it is opened at 921600 baud. + +There are two run time settings that control the verbosity, the most verbose settings being: + +``` +log_level = DEBUG +Allowed values: ERROR, WARNING, INFO, VERBOSE, DEBUG + +log_topics = 0 +Allowed range: 0 - 4294967295 + +``` + +The use of level and topics is described in the following sections. + +## LOG LEVELS + +Log levels are defined in `src/main/common/log.h`, at the time of writing these include (in ascending order): + +* ERROR +* WARNING +* INFO +* VERBOSE +* DEBUG + +These are used at both compile time and run time. + +At compile time, a maximum level may be defined. As of iNav 2.3, for F3 targets the maximum level is ERROR, for F4/F7 the maximum level is DEBUG. + +At run time, the level defines the level that will be displayed, so for a F4 or F7 target that has compile time suport for all log levels, if the CLI sets +``` +log_level = INFO +``` +then only `ERROR`, `WARNING` and `INFO` levels will be output. + +## Log Topic + +Log levels are defined in `src/main/common/log.h`, at the time of writing: + +* SYSTEM +* GYRO +* BARO +* PITOT +* PWM +* TIMER +* IMU +* TEMPERATURE +* POS_ESTIMATOR +* VTX +* OSD + +Topics are stored as masks (SYSTEM=1 ... OSD=1024) and may be used to unconditionally display log messages. + +If the CLI `log_topics` is non-zero, then all topics matching the mask will be displayed regardless of `log_level`. Setting `log_topics` to 4294967295 (all bits set) will display all log messages regardless of run time level (but still constrained by compile time settings), so F3 will still only display ERROR level messages. + +## Code usage + +A set of macros `LOG_S()` (log system) through `LOG_D()` (log debug) may be used, subject to compile time log level constraints. These provide `printf` style logging for a given topic. + +``` +// LOG_D(topic, fmt, ...) +LOG_D(SYSTEM, "This is %s topic debug message, value %d", "system", 42); +``` + +It is also possible to dump a hex representation of arbitrary data: + +``` +// LOG_BUF_D(topic, buf, size) + +struct {...} tstruct; +... +LOG_BUF_D(TEMPERATURE, &tstruct, sizeof(tstruct)); + +``` + +## Output Support + +Log messages are transmitted through the `FUNCTION_LOG` serial port as MSP messages (`MSP_DEBUGMSG`). It is possible to use any serial terminal to display these messages, however it is advisable to use an application that understands `MSP_DEBUGMSG` in order to maintain readability (in a raw serial terminal the MSP message envelope may result in the display of strange characters). `MSP_DEBUGMSG` aware applications include: + +* msp-tool https://github.com/fiam/msp-tool +* mwp https://github.com/stronnag/mwptools +* iNav Configurator + +For example, with the final lines of `src/main/fc/fc_init.c` set to: + +``` + LOG_E(SYSTEM, "Init is complete"); + systemState |= SYSTEM_STATE_READY; +``` + +and the following CLI settings: + +``` +serial 20 32769 115200 115200 0 115200 +set log_level = DEBUG +set log_topics = 4294967295 +``` + +The output will be formatted as follows: + +``` +# msp-tool +[DEBUG] [ 3.967] Init is complete +# mwp (stderr log file) +2020-02-02T19:09:02+0000 DEBUG:[ 3.968] Init is complete +``` + +The numeric value in square brackets is the FC uptime in seconds. From 7a8e1cb8e096d5df0a1ee9de5659713ae2a33a1d Mon Sep 17 00:00:00 2001 From: Hydra Date: Tue, 4 Feb 2020 15:18:16 +0100 Subject: [PATCH 108/110] Allow compilation when `USE_SERIALRX_IBUS` is not defined. * linker errors occur otherwise. --- src/main/telemetry/telemetry.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 92ce74576f3..88a30091bee 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -190,7 +190,7 @@ void telemetryProcess(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); // since not used by all the telemetry protocols - #if defined(USE_TELEMETRY_FRSKY) +#if defined(USE_TELEMETRY_FRSKY) handleFrSkyTelemetry(); #endif @@ -214,7 +214,7 @@ void telemetryProcess(timeUs_t currentTimeUs) handleJetiExBusTelemetry(); #endif -#if defined(USE_TELEMETRY_IBUS) +#if defined(USE_SERIALRX_IBUS) && defined(USE_TELEMETRY_IBUS) handleIbusTelemetry(); #endif From 769801fb1af6f46962d96eaca38426802f63453c Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 8 Feb 2020 14:06:53 +0000 Subject: [PATCH 109/110] remove obsolete nav_mc_pos_xy_[id] settings from Cli.md --- docs/Cli.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 802a00a341b..4959469d4e2 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -363,8 +363,6 @@ A shorter form is also supported to enable and disable functions using `serial < | nav_mc_vel_z_i | 50 | I gain of velocity PID controller | | nav_mc_vel_z_d | 10 | D gain of velocity PID controller | | nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | -| nav_mc_pos_xy_i | 120 | Controls deceleration time. Measured in 1/100 sec. Expected hold position is placed at a distance calculated as decelerationTime * currentVelocity | -| nav_mc_pos_xy_d | 10 | | | nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | | nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | | nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | From d33db1dfc3d838ef1212ec0db6e19377baad2f7f Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sat, 8 Feb 2020 19:12:30 +0100 Subject: [PATCH 110/110] [MAMBA] Fix DSHOT issue on MAMBAF722 and MAMBAF405 targets --- src/main/target/FURYF4OSD/target.c | 8 ++++---- src/main/target/MAMBAF405US/target.c | 2 +- src/main/target/MAMBAF722/target.c | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/target/FURYF4OSD/target.c b/src/main/target/FURYF4OSD/target.c index 56881d7c814..e9999e71eb2 100644 --- a/src/main/target/FURYF4OSD/target.c +++ b/src/main/target/FURYF4OSD/target.c @@ -24,10 +24,10 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT - DMA1_ST6_CH3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT - DMA1_ST7_CH5 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DMA2_ST6_CH0 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S4_OUT - DMA1_ST1_CH3 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT - D(1, 6, 3) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT - D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - D(1, 2, 5) + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S4_OUT - D(1, 1, 3) DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), DEF_TIM(TIM2, CH4, PB11, TIM_USE_ANY, 0, 0), DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH6 diff --git a/src/main/target/MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c index c79517e87f1..d8e1c39129c 100644 --- a/src/main/target/MAMBAF405US/target.c +++ b/src/main/target/MAMBAF405US/target.c @@ -27,7 +27,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 1 ), // S4_OUT – D(2, 2, 6) DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6) DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7) DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7) diff --git a/src/main/target/MAMBAF722/target.c b/src/main/target/MAMBAF722/target.c index 14a8bf172f7..6ed573e6b64 100644 --- a/src/main/target/MAMBAF722/target.c +++ b/src/main/target/MAMBAF722/target.c @@ -30,7 +30,7 @@ const timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7) DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7) DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 1 ), // S4_OUT – D(2, 2, 6) DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) };