diff --git a/Arduino/ODriveArduino/ODriveArduino.cpp b/Arduino/ODriveArduino/ODriveArduino.cpp index 00fce19ad..3f4eab5ae 100644 --- a/Arduino/ODriveArduino/ODriveArduino.cpp +++ b/Arduino/ODriveArduino/ODriveArduino.cpp @@ -50,6 +50,11 @@ float ODriveArduino::readFloat() { return readString().toFloat(); } +float ODriveArduino::GetVelocity(int motor_number){ + serial_<< "r axis" << motor_number << ".encoder.vel_estimate\n"; + return ODriveArduino::readFloat(); +} + int32_t ODriveArduino::readInt() { return readString().toInt(); } diff --git a/Arduino/ODriveArduino/ODriveArduino.h b/Arduino/ODriveArduino/ODriveArduino.h index 86b3aaf14..8e39b244f 100644 --- a/Arduino/ODriveArduino/ODriveArduino.h +++ b/Arduino/ODriveArduino/ODriveArduino.h @@ -28,6 +28,8 @@ class ODriveArduino { void SetVelocity(int motor_number, float velocity, float current_feedforward); void SetCurrent(int motor_number, float current); void TrapezoidalMove(int motor_number, float position); + // Getters + float GetVelocity(int motor_number); // General params float readFloat(); int32_t readInt(); diff --git a/CHANGELOG.md b/CHANGELOG.md index 7842f986b..8102a27ec 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,6 +1,15 @@ # Unreleased Features Please add a note of your changes below this heading if you make a Pull Request. +# Releases +## [0.4.11] - 2019-07-25 +### Added +* Separate lockin configs for sensorless, index search, and general. +* Check current limit violation: added `ERROR_CURRENT_UNSTABLE`, `motor.config.current_lim_tolerance`. + +### Changed +* Ascii command for reboot changed from `sb` to `sr`. + # Releases ## [0.4.10] - 2019-04-24 ### Fixed diff --git a/Firmware/.clang-format b/Firmware/.clang-format new file mode 100644 index 000000000..eac508732 --- /dev/null +++ b/Firmware/.clang-format @@ -0,0 +1,7 @@ +--- +BasedOnStyle: Google +AlignConsecutiveAssignments: 'true' +AllowShortCaseLabelsOnASingleLine: 'true' +IndentWidth: '4' + +... diff --git a/Firmware/.vscode/launch.json b/Firmware/.vscode/launch.json index 71e7db4c2..48fecec2e 100644 --- a/Firmware/.vscode/launch.json +++ b/Firmware/.vscode/launch.json @@ -15,6 +15,7 @@ "interface/stlink-v2.cfg", "target/stm32f4x_stlink.cfg", ], + "svdFile": "${workspaceRoot}/Board/v3/STM32F40x.svd", "cwd": "${workspaceRoot}" }, { diff --git a/Firmware/.vscode/settings.json b/Firmware/.vscode/settings.json index 63c1463bd..39c28f829 100644 --- a/Firmware/.vscode/settings.json +++ b/Firmware/.vscode/settings.json @@ -1,5 +1,4 @@ { - "C_Cpp.clang_format_style": "{ BasedOnStyle: Google, IndentWidth: 4, ColumnLimit: 0 }", "C_Cpp.intelliSenseEngine": "Default", "C_Cpp.intelliSenseEngineFallback": "Disabled", "files.exclude": { diff --git a/Firmware/Board/v3/Drivers/CMSIS/Include/cmsis_gcc.h b/Firmware/Board/v3/Drivers/CMSIS/Include/cmsis_gcc.h index bb89fbba9..3e522777c 100644 --- a/Firmware/Board/v3/Drivers/CMSIS/Include/cmsis_gcc.h +++ b/Firmware/Board/v3/Drivers/CMSIS/Include/cmsis_gcc.h @@ -161,7 +161,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) { - __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : ); } @@ -187,7 +187,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) { - __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : ); } diff --git a/Firmware/Board/v3/STM32F40x.svd b/Firmware/Board/v3/STM32F40x.svd new file mode 100644 index 000000000..3ead47277 --- /dev/null +++ b/Firmware/Board/v3/STM32F40x.svd @@ -0,0 +1,54146 @@ + + + STM32F40x + 1.5 + STM32F40x + + + 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 + + + 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 + + + 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 + 0x400 + 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 + + + + 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 + 0x400 + 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 + no description available + 0 + 1 + + + HU + no description available + 1 + 1 + + + HM + no description available + 2 + 1 + + + DAIF + no description available + 3 + 1 + + + RAM + no description available + 4 + 1 + + + BFD + no description available + 5 + 1 + + + PCF + no description available + 6 + 1 + + + SAIF + no description available + 7 + 1 + + + SAF + no description available + 8 + 1 + + + HPF + no description available + 9 + 1 + + + RA + no description available + 31 + 1 + + + + + MACHTHR + MACHTHR + Ethernet MAC hash table high + register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + no description available + 0 + 32 + + + + + MACHTLR + MACHTLR + Ethernet MAC hash table low + register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + no description available + 0 + 32 + + + + + MACMIIAR + MACMIIAR + Ethernet MAC MII address + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + no description available + 0 + 1 + + + MW + no description available + 1 + 1 + + + CR + no description available + 2 + 3 + + + MR + no description available + 6 + 5 + + + PA + no description available + 11 + 5 + + + + + MACMIIDR + MACMIIDR + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + TD + no description available + 0 + 16 + + + + + MACFCR + MACFCR + Ethernet MAC flow control + register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB + no description available + 0 + 1 + + + TFCE + no description available + 1 + 1 + + + RFCE + no description available + 2 + 1 + + + UPFD + no description available + 3 + 1 + + + PLT + no description available + 4 + 2 + + + ZQPD + no description available + 7 + 1 + + + PT + no description available + 16 + 16 + + + + + MACVLANTR + MACVLANTR + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VLANTI + no description available + 0 + 16 + + + VLANTC + no description available + 16 + 1 + + + + + MACPMTCSR + MACPMTCSR + Ethernet MAC PMT control and status + register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + no description available + 0 + 1 + + + MPE + no description available + 1 + 1 + + + WFE + no description available + 2 + 1 + + + MPR + no description available + 5 + 1 + + + WFR + no description available + 6 + 1 + + + GU + no description available + 9 + 1 + + + WFFRPR + no description available + 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 + no description available + 3 + 1 + read-only + + + MMCS + no description available + 4 + 1 + read-only + + + MMCRS + no description available + 5 + 1 + read-only + + + MMCTS + no description available + 6 + 1 + read-only + + + TSTS + no description available + 9 + 1 + read-write + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask + register + 0x3C + 0x20 + read-write + 0x00000000 + + + PMTIM + no description available + 3 + 1 + + + TSTIM + no description available + 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 + no description available + 0 + 16 + + + MBC + no description available + 24 + 6 + + + SA + no description available + 30 + 1 + + + AE + no description available + 31 + 1 + + + + + MACA1LR + MACA1LR + Ethernet MAC address1 low + register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MACA1LR + no description available + 0 + 32 + + + + + MACA2HR + MACA2HR + Ethernet MAC address 2 high + register + 0x50 + 0x20 + read-write + 0x0000FFFF + + + MAC2AH + no description available + 0 + 16 + + + MBC + no description available + 24 + 6 + + + SA + no description available + 30 + 1 + + + AE + no description available + 31 + 1 + + + + + MACA2LR + MACA2LR + Ethernet MAC address 2 low + register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MACA2L + no description available + 0 + 31 + + + + + MACA3HR + MACA3HR + Ethernet MAC address 3 high + register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MACA3H + no description available + 0 + 16 + + + MBC + no description available + 24 + 6 + + + SA + no description available + 30 + 1 + + + AE + no description available + 31 + 1 + + + + + MACA3LR + MACA3LR + Ethernet MAC address 3 low + register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MBCA3L + no description available + 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 + no description available + 0 + 1 + + + CSR + no description available + 1 + 1 + + + ROR + no description available + 2 + 1 + + + MCF + no description available + 3 + 1 + + + MCP + no description available + 4 + 1 + + + MCFHP + no description available + 5 + 1 + + + + + MMCRIR + MMCRIR + Ethernet MMC receive interrupt + register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCES + no description available + 5 + 1 + + + RFAES + no description available + 6 + 1 + + + RGUFS + no description available + 17 + 1 + + + + + MMCTIR + MMCTIR + Ethernet MMC transmit interrupt + register + 0x8 + 0x20 + read-only + 0x00000000 + + + TGFSCS + no description available + 14 + 1 + + + TGFMSCS + no description available + 15 + 1 + + + TGFS + no description available + 21 + 1 + + + + + MMCRIMR + MMCRIMR + Ethernet MMC receive interrupt mask + register + 0xC + 0x20 + read-write + 0x00000000 + + + RFCEM + no description available + 5 + 1 + + + RFAEM + no description available + 6 + 1 + + + RGUFM + no description available + 17 + 1 + + + + + MMCTIMR + MMCTIMR + Ethernet MMC transmit interrupt mask + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TGFSCM + no description available + 14 + 1 + + + TGFMSCM + no description available + 15 + 1 + + + TGFM + no description available + 16 + 1 + + + + + MMCTGFSCCR + MMCTGFSCCR + Ethernet MMC transmitted good frames after a + single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + no description available + 0 + 32 + + + + + MMCTGFMSCCR + MMCTGFMSCCR + Ethernet MMC transmitted good frames after + more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + no description available + 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 + no description available + 0 + 32 + + + + + MMCRFAECR + MMCRFAECR + Ethernet MMC received frames with alignment + error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + no description available + 0 + 32 + + + + + MMCRGUFCR + MMCRGUFCR + MMC received good unicast frames counter + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + no description available + 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 + no description available + 0 + 1 + + + TSFCU + no description available + 1 + 1 + + + TSPTPPSV2E + no description available + 10 + 1 + + + TSSPTPOEFE + no description available + 11 + 1 + + + TSSIPV6FE + no description available + 12 + 1 + + + TSSIPV4FE + no description available + 13 + 1 + + + TSSEME + no description available + 14 + 1 + + + TSSMRME + no description available + 15 + 1 + + + TSCNT + no description available + 16 + 2 + + + TSPFFMAE + no description available + 18 + 1 + + + TSSTI + no description available + 2 + 1 + + + TSSTU + no description available + 3 + 1 + + + TSITE + no description available + 4 + 1 + + + TTSARU + no description available + 5 + 1 + + + TSSARFE + no description available + 8 + 1 + + + TSSSR + no description available + 9 + 1 + + + + + PTPSSIR + PTPSSIR + Ethernet PTP subsecond increment + register + 0x4 + 0x20 + read-write + 0x00000000 + + + STSSI + no description available + 0 + 8 + + + + + PTPTSHR + PTPTSHR + Ethernet PTP time stamp high + register + 0x8 + 0x20 + read-only + 0x00000000 + + + STS + no description available + 0 + 32 + + + + + PTPTSLR + PTPTSLR + Ethernet PTP time stamp low + register + 0xC + 0x20 + read-only + 0x00000000 + + + STSS + no description available + 0 + 31 + + + STPNS + no description available + 31 + 1 + + + + + PTPTSHUR + PTPTSHUR + Ethernet PTP time stamp high update + register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSUS + no description available + 0 + 32 + + + + + PTPTSLUR + PTPTSLUR + Ethernet PTP time stamp low update + register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSUSS + no description available + 0 + 31 + + + TSUPNS + no description available + 31 + 1 + + + + + PTPTSAR + PTPTSAR + Ethernet PTP time stamp addend + register + 0x18 + 0x20 + read-write + 0x00000000 + + + TSA + no description available + 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 + no description available + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status + register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSSO + no description available + 0 + 1 + + + TSTTR + no description available + 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 + no description available + 0 + 1 + + + DA + no description available + 1 + 1 + + + DSL + no description available + 2 + 5 + + + EDFE + no description available + 7 + 1 + + + PBL + no description available + 8 + 6 + + + RTPR + no description available + 14 + 2 + + + FB + no description available + 16 + 1 + + + RDP + no description available + 17 + 6 + + + USP + no description available + 23 + 1 + + + FPM + no description available + 24 + 1 + + + AAB + no description available + 25 + 1 + + + MB + no description available + 26 + 1 + + + + + DMATPDR + DMATPDR + Ethernet DMA transmit poll demand + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + no description available + 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 + no description available + 0 + 32 + + + + + DMATDLAR + DMATDLAR + Ethernet DMA transmit descriptor list + address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + no description available + 0 + 32 + + + + + DMASR + DMASR + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TS + no description available + 0 + 1 + read-write + + + TPSS + no description available + 1 + 1 + read-write + + + TBUS + no description available + 2 + 1 + read-write + + + TJTS + no description available + 3 + 1 + read-write + + + ROS + no description available + 4 + 1 + read-write + + + TUS + no description available + 5 + 1 + read-write + + + RS + no description available + 6 + 1 + read-write + + + RBUS + no description available + 7 + 1 + read-write + + + RPSS + no description available + 8 + 1 + read-write + + + PWTS + no description available + 9 + 1 + read-write + + + ETS + no description available + 10 + 1 + read-write + + + FBES + no description available + 13 + 1 + read-write + + + ERS + no description available + 14 + 1 + read-write + + + AIS + no description available + 15 + 1 + read-write + + + NIS + no description available + 16 + 1 + read-write + + + RPS + no description available + 17 + 3 + read-only + + + TPS + no description available + 20 + 3 + read-only + + + EBS + no description available + 23 + 3 + read-only + + + MMCS + no description available + 27 + 1 + read-only + + + PMTS + no description available + 28 + 1 + read-only + + + TSTS + no description available + 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 + no description available + 0 + 1 + + + TPSIE + no description available + 1 + 1 + + + TBUIE + no description available + 2 + 1 + + + TJTIE + no description available + 3 + 1 + + + ROIE + no description available + 4 + 1 + + + TUIE + no description available + 5 + 1 + + + RIE + no description available + 6 + 1 + + + RBUIE + no description available + 7 + 1 + + + RPSIE + no description available + 8 + 1 + + + RWTIE + no description available + 9 + 1 + + + ETIE + no description available + 10 + 1 + + + FBEIE + no description available + 13 + 1 + + + ERIE + no description available + 14 + 1 + + + AISE + no description available + 15 + 1 + + + NISE + no description available + 16 + 1 + + + + + DMAMFBOCR + DMAMFBOCR + Ethernet DMA missed frame and buffer + overflow counter register + 0x20 + 0x20 + read-write + 0x00000000 + + + MFC + no description available + 0 + 16 + + + OMFC + no description available + 16 + 1 + + + MFA + no description available + 17 + 11 + + + OFOC + no description available + 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 + no description available + 0 + 32 + + + + + DMACHRBAR + DMACHRBAR + Ethernet DMA current host receive buffer + address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + no description available + 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 + 0xFFFC0400 + registers + + + 0xFFFC0400 + 0x40000 + reserved + + + 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 + + + 0x3F200 + 0xFFFC1200 + reserved + + + + 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 + 0xE000E000 + + 0x0 + 0x1001 + registers + + + 0x1001 + 0xFFFFF3FF + reserved + + + + ICTR + ICTR + Interrupt Controller Type + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + INTLINESNUM + Total number of interrupt lines in + groups + 0 + 4 + + + + + STIR + STIR + Software Triggered Interrupt + Register + 0xF00 + 0x20 + write-only + 0x00000000 + + + INTID + interrupt to be triggered + 0 + 9 + + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x200 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x204 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x208 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x280 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x284 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x288 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x300 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x304 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x308 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x400 + 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 + 0x404 + 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 + 0x408 + 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 + 0x40C + 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 + 0x410 + 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 + 0x414 + 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 + 0x418 + 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 + 0x41C + 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 + 0x420 + 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 + 0x424 + 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 + 0x428 + 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 + 0x42C + 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 + 0x430 + 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 + 0x434 + 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 + 0x438 + 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 + 0x43C + 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 + 0x440 + 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 + 0x444 + 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 + 0x448 + 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 + 0x44C + 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 + + + + + + + diff --git a/Firmware/MotorControl/axis.cpp b/Firmware/MotorControl/axis.cpp index 80987c000..e5f25b163 100644 --- a/Firmware/MotorControl/axis.cpp +++ b/Firmware/MotorControl/axis.cpp @@ -6,14 +6,16 @@ #include "utils.h" #include "odrive_main.h" -Axis::Axis(const AxisHardwareConfig_t& hw_config, +Axis::Axis(int axis_num, + const AxisHardwareConfig_t& hw_config, Config_t& config, Encoder& encoder, SensorlessEstimator& sensorless_estimator, Controller& controller, Motor& motor, TrapezoidalTrajectory& trap) - : hw_config_(hw_config), + : axis_num_(axis_num), + hw_config_(hw_config), config_(config), encoder_(encoder), sensorless_estimator_(sensorless_estimator), @@ -31,6 +33,34 @@ Axis::Axis(const AxisHardwareConfig_t& hw_config, update_watchdog_settings(); } +Axis::LockinConfig_t Axis::default_calibration() { + Axis::LockinConfig_t config; + config.current = 10.0f; // [A] + config.ramp_time = 0.4f; // [s] + config.ramp_distance = 1 * M_PI; // [rad] + config.accel = 20.0f; // [rad/s^2] + config.vel = 40.0f; // [rad/s] + config.finish_distance = 100.0f * 2.0f * M_PI; // [rad] + config.finish_on_vel = false; + config.finish_on_distance = true; + config.finish_on_enc_idx = true; + return config; +} + +Axis::LockinConfig_t Axis::default_sensorless() { + Axis::LockinConfig_t config; + config.current = 10.0f; // [A] + config.ramp_time = 0.4f; // [s] + config.ramp_distance = 1 * M_PI; // [rad] + config.accel = 200.0f; // [rad/s^2] + config.vel = 400.0f; // [rad/s] + config.finish_distance = 100.0f; // [rad] + config.finish_on_vel = true; + config.finish_on_distance = false; + config.finish_on_enc_idx = false; + return config; +} + static void step_cb_wrapper(void* ctx) { reinterpret_cast(ctx)->step_cb(); } @@ -177,32 +207,32 @@ bool Axis::watchdog_check() { } } -bool Axis::run_lockin_spin() { +bool Axis::run_lockin_spin(const LockinConfig_t &lockin_config) { // Spiral up current for softer rotor lock-in lockin_state_ = LOCKIN_STATE_RAMP; float x = 0.0f; run_control_loop([&]() { - float phase = wrap_pm_pi(config_.lockin.ramp_distance * x); - float I_mag = config_.lockin.current * x; - x += current_meas_period / config_.lockin.ramp_time; + float phase = wrap_pm_pi(lockin_config.ramp_distance * x); + float I_mag = lockin_config.current * x; + x += current_meas_period / lockin_config.ramp_time; if (!motor_.update(I_mag, phase, 0.0f)) return false; return x < 1.0f; }); // Spin states - float distance = config_.lockin.ramp_distance; + float distance = lockin_config.ramp_distance; float phase = wrap_pm_pi(distance); - float vel = distance / config_.lockin.ramp_time; + float vel = distance / lockin_config.ramp_time; // Function of states to check if we are done auto spin_done = [&](bool vel_override = false) -> bool { bool done = false; - if (config_.lockin.finish_on_vel || vel_override) - done = done || fabsf(vel) >= fabsf(config_.lockin.vel); - if (config_.lockin.finish_on_distance) - done = done || fabsf(distance) >= fabsf(config_.lockin.finish_distance); - if (config_.lockin.finish_on_enc_idx) + if (lockin_config.finish_on_vel || vel_override) + done = done || fabsf(vel) >= fabsf(lockin_config.vel); + if (lockin_config.finish_on_distance) + done = done || fabsf(distance) >= fabsf(lockin_config.finish_distance); + if (lockin_config.finish_on_enc_idx) done = done || encoder_.index_found_; return done; }; @@ -210,11 +240,11 @@ bool Axis::run_lockin_spin() { // Accelerate lockin_state_ = LOCKIN_STATE_ACCELERATE; run_control_loop([&]() { - vel += config_.lockin.accel * current_meas_period; + vel += lockin_config.accel * current_meas_period; distance += vel * current_meas_period; phase = wrap_pm_pi(phase + vel * current_meas_period); - if (!motor_.update(config_.lockin.current, phase, vel)) + if (!motor_.update(lockin_config.current, phase, vel)) return false; return !spin_done(true); //vel_override to go to next phase }); @@ -225,12 +255,12 @@ bool Axis::run_lockin_spin() { // Constant speed if (!spin_done()) { lockin_state_ = LOCKIN_STATE_CONST_VEL; - vel = config_.lockin.vel; // reset to actual specified vel to avoid small integration error + vel = lockin_config.vel; // reset to actual specified vel to avoid small integration error run_control_loop([&]() { distance += vel * current_meas_period; phase = wrap_pm_pi(phase + vel * current_meas_period); - if (!motor_.update(config_.lockin.current, phase, vel)) + if (!motor_.update(lockin_config.current, phase, vel)) return false; return !spin_done(); }); @@ -369,17 +399,17 @@ void Axis::run_state_machine_loop() { case AXIS_STATE_LOCKIN_SPIN: { if (!motor_.is_calibrated_ || motor_.config_.direction==0) goto invalid_state_label; - status = run_lockin_spin(); + status = run_lockin_spin(config_.lockin); } break; case AXIS_STATE_SENSORLESS_CONTROL: { if (!motor_.is_calibrated_ || motor_.config_.direction==0) goto invalid_state_label; - status = run_lockin_spin(); // TODO: restart if desired + status = run_lockin_spin(config_.sensorless_ramp); // TODO: restart if desired if (status) { // call to controller.reset() that happend when arming means that vel_setpoint // is zeroed. So we make the setpoint the spinup target for smooth transition. - controller_.vel_setpoint_ = config_.lockin.vel; + controller_.vel_setpoint_ = config_.sensorless_ramp.vel; status = run_sensorless_control_loop(); } } break; diff --git a/Firmware/MotorControl/axis.hpp b/Firmware/MotorControl/axis.hpp index 9e78fdab9..c23fb2f13 100644 --- a/Firmware/MotorControl/axis.hpp +++ b/Firmware/MotorControl/axis.hpp @@ -49,6 +49,10 @@ class Axis { bool finish_on_enc_idx = false; }; + static LockinConfig_t default_calibration(); + static LockinConfig_t default_sensorless(); + static LockinConfig_t default_lockin(); + struct Config_t { bool startup_motor_calibration = false; //(ctx)->decode_step_dir_pins(); }, this), make_protocol_property("dir_gpio_pin", &config_.dir_gpio_pin, [](void* ctx) { static_cast(ctx)->decode_step_dir_pins(); }, this), - make_protocol_object("lockin", + make_protocol_object("calibration_lockin", + make_protocol_property("current", &config_.calibration_lockin.current), + make_protocol_property("ramp_time", &config_.calibration_lockin.ramp_time), + make_protocol_property("ramp_distance", &config_.calibration_lockin.ramp_distance), + make_protocol_property("accel", &config_.calibration_lockin.accel), + make_protocol_property("vel", &config_.calibration_lockin.vel) + ), + make_protocol_object("sensorless_ramp", + make_protocol_property("current", &config_.sensorless_ramp.current), + make_protocol_property("ramp_time", &config_.sensorless_ramp.ramp_time), + make_protocol_property("ramp_distance", &config_.sensorless_ramp.ramp_distance), + make_protocol_property("accel", &config_.sensorless_ramp.accel), + make_protocol_property("vel", &config_.sensorless_ramp.vel), + make_protocol_property("finish_distance", &config_.sensorless_ramp.finish_distance), + make_protocol_property("finish_on_vel", &config_.sensorless_ramp.finish_on_vel), + make_protocol_property("finish_on_distance", &config_.sensorless_ramp.finish_on_distance), + make_protocol_property("finish_on_enc_idx", &config_.sensorless_ramp.finish_on_enc_idx) + ), + make_protocol_object("general_lockin", make_protocol_property("current", &config_.lockin.current), make_protocol_property("ramp_time", &config_.lockin.ramp_time), make_protocol_property("ramp_distance", &config_.lockin.ramp_distance), diff --git a/Firmware/MotorControl/encoder.cpp b/Firmware/MotorControl/encoder.cpp index 374d882be..7dcdd57a2 100644 --- a/Firmware/MotorControl/encoder.cpp +++ b/Firmware/MotorControl/encoder.cpp @@ -93,6 +93,8 @@ void Encoder::set_linear_count(int32_t count) { // Update states shadow_count_ = count; pos_estimate_ = (float)count; + tim_cnt_sample_ = count; + //Write hardware last hw_config_.timer->Instance->CNT = count; @@ -125,20 +127,17 @@ bool Encoder::run_index_search() { } set_idx_subscribe(); - bool orig_finish_on_enc_idx = axis_->config_.lockin.finish_on_enc_idx; - axis_->config_.lockin.finish_on_enc_idx = true; - bool status = axis_->run_lockin_spin(); - axis_->config_.lockin.finish_on_enc_idx = orig_finish_on_enc_idx; + bool status = axis_->run_lockin_spin(axis_->config_.calibration_lockin); return status; } bool Encoder::run_direction_find() { int32_t init_enc_val = shadow_count_; - bool orig_finish_on_distance = axis_->config_.lockin.finish_on_distance; - axis_->config_.lockin.finish_on_distance = true; + bool orig_finish_on_distance = axis_->config_.calibration_lockin.finish_on_distance; + axis_->config_.calibration_lockin.finish_on_distance = true; axis_->motor_.config_.direction = 1; // Must test spin forwards for direction detect logic - bool status = axis_->run_lockin_spin(); - axis_->config_.lockin.finish_on_distance = orig_finish_on_distance; + bool status = axis_->run_lockin_spin(axis_->config_.calibration_lockin); + axis_->config_.calibration_lockin.finish_on_distance = orig_finish_on_distance; if (status) { // Check response and direction diff --git a/Firmware/MotorControl/main.cpp b/Firmware/MotorControl/main.cpp index 427792b36..d5acf2525 100644 --- a/Firmware/MotorControl/main.cpp +++ b/Firmware/MotorControl/main.cpp @@ -169,7 +169,7 @@ int odrive_main(void) { hw_configs[i].gate_driver_config, motor_configs[i]); TrapezoidalTrajectory *trap = new TrapezoidalTrajectory(trap_configs[i]); - axes[i] = new Axis(hw_configs[i].axis_config, axis_configs[i], + axes[i] = new Axis(i, hw_configs[i].axis_config, axis_configs[i], *encoder, *sensorless_estimator, *controller, *motor, *trap); } diff --git a/Firmware/MotorControl/motor.cpp b/Firmware/MotorControl/motor.cpp index 6fa01cc80..2a9cd7031 100644 --- a/Firmware/MotorControl/motor.cpp +++ b/Firmware/MotorControl/motor.cpp @@ -342,6 +342,7 @@ bool Motor::FOC_current(float Id_des, float Iq_des, float I_phase, float pwm_pha if (fabsf(current_meas_.phB) > ictrl.overcurrent_trip_level || fabsf(current_meas_.phC) > ictrl.overcurrent_trip_level) { set_error(ERROR_CURRENT_SENSE_SATURATION); + return false; } // Clarke transform @@ -356,6 +357,13 @@ bool Motor::FOC_current(float Id_des, float Iq_des, float I_phase, float pwm_pha ictrl.Iq_measured += ictrl.I_measured_report_filter_k * (Iq - ictrl.Iq_measured); ictrl.Id_measured += ictrl.I_measured_report_filter_k * (Id - ictrl.Id_measured); + // Check for violation of current limit + float I_trip = config_.current_lim_tolerance * effective_current_lim(); + if (SQ(Id) + SQ(Iq) > SQ(I_trip)) { + set_error(ERROR_CURRENT_UNSTABLE); + return false; + } + // Current error float Ierr_d = Id_des - Id; float Ierr_q = Iq_des - Iq; diff --git a/Firmware/MotorControl/motor.hpp b/Firmware/MotorControl/motor.hpp index 279e68489..d31985eed 100644 --- a/Firmware/MotorControl/motor.hpp +++ b/Firmware/MotorControl/motor.hpp @@ -22,7 +22,8 @@ class Motor { ERROR_BRAKE_DEADTIME_VIOLATION = 0x0100, ERROR_UNEXPECTED_TIMER_CALLBACK = 0x0200, ERROR_CURRENT_SENSE_SATURATION = 0x0400, - ERROR_INVERTER_OVER_TEMP = 0x0800 + ERROR_INVERTER_OVER_TEMP = 0x0800, + ERROR_CURRENT_UNSTABLE = 0x1000 }; enum MotorType_t { @@ -68,6 +69,7 @@ class Motor { // Read out max_allowed_current to see max supported value for current_lim. // float current_lim = 70.0f; //[A] float current_lim = 10.0f; //[A] + float current_lim_tolerance = 1.25f; // multiple of current_lim // Value used to compute shunt amplifier gains float requested_current_range = 60.0f; // [A] float current_control_bandwidth = 1000.0f; // [rad/s] @@ -227,6 +229,7 @@ class Motor { make_protocol_property("direction", &config_.direction), make_protocol_property("motor_type", &config_.motor_type), make_protocol_property("current_lim", &config_.current_lim), + make_protocol_property("current_lim_tolerance", &config_.current_lim_tolerance), make_protocol_property("inverter_temp_limit_lower", &config_.inverter_temp_limit_lower), make_protocol_property("inverter_temp_limit_upper", &config_.inverter_temp_limit_upper), make_protocol_property("requested_current_range", &config_.requested_current_range), diff --git a/Firmware/communication/ascii_protocol.cpp b/Firmware/communication/ascii_protocol.cpp index 1e1c9ba4a..1cb5f7941 100644 --- a/Firmware/communication/ascii_protocol.cpp +++ b/Firmware/communication/ascii_protocol.cpp @@ -210,7 +210,7 @@ void ASCII_protocol_process_line(const uint8_t* buffer, size_t len, StreamSink& save_configuration(); } else if (cmd[1] == 'e'){ // Erase config erase_configuration(); - } else if (cmd[1] == 'b'){ // Reboot + } else if (cmd[1] == 'r'){ // Reboot NVIC_SystemReset(); } diff --git a/Firmware/fibre/cpp/include/fibre/protocol.hpp b/Firmware/fibre/cpp/include/fibre/protocol.hpp index 498d51720..c1f3cc680 100644 --- a/Firmware/fibre/cpp/include/fibre/protocol.hpp +++ b/Firmware/fibre/cpp/include/fibre/protocol.hpp @@ -976,17 +976,17 @@ class ProtocolFunction, std::tuple> : output_properties_.register_endpoints(list, id + 1 + decltype(input_properties_)::endpoint_count, length); } - template std::enable_if_t + template std::enable_if_t handle_ex() { invoke_function_with_tuple(*obj_, func_ptr_, in_args_); } - template std::enable_if_t + template std::enable_if_t handle_ex() { std::get<0>(out_args_) = invoke_function_with_tuple(*obj_, func_ptr_, in_args_); } - template std::enable_if_t= 2> + template std::enable_if_t= 2> handle_ex() { out_args_ = invoke_function_with_tuple(*obj_, func_ptr_, in_args_); } @@ -997,7 +997,7 @@ class ProtocolFunction, std::tuple> : (void) output; LOG_FIBRE("tuple still at %x and of size %u\r\n", (uintptr_t)&in_args_, sizeof(in_args_)); LOG_FIBRE("invoke function using %d and %.3f\r\n", std::get<0>(in_args_), std::get<1>(in_args_)); - handle_ex(); + handle_ex(); } const char * name_; diff --git a/docs/ascii-protocol.md b/docs/ascii-protocol.md index db6869a84..a0757e2fe 100644 --- a/docs/ascii-protocol.md +++ b/docs/ascii-protocol.md @@ -136,4 +136,4 @@ Not all parameters can be accessed via the ASCII protocol but at least all param #### System commands: * `ss` - Save config * `se` - Erase config -* `sb` - Reboot +* `sr` - Reboot diff --git a/docs/encoders.md b/docs/encoders.md index c3d42fb03..c9a8aaab7 100644 --- a/docs/encoders.md +++ b/docs/encoders.md @@ -40,9 +40,15 @@ Below are the steps to do the one-time calibration and configuration. Note that That's it, now on every reboot the motor will turn in one direction until it finds the encoder index. -* If you wish to scan for the index pulse in the other direction, that feature is currently undocumented. * If your motor has problems reaching the index location due to the mechanical load, you can increase `.motor.config.calibration_current`. +### Reversing index search +Sometimes you would like the index search to only happen in a particular direction (the reverse of the default), instead of swapping the motor leads, you can ensure the following three values are negative: +* `.config.calibration_lockin.vel` +* `.config.calibration_lockin.accel` +* `.config.calibration_lockin.ramp_distance` + + *IMPORTANT:* Your motor should find the same rotational position when the ODrive performs an index search if the index signal is working properly. This means that the motor should spin, and stop at the same position if you have set .config.startup_encoder_index_search so the search starts on reboot, or you if call the command:.requested_state = AXIS_STATE_ENCODER_INDEX_SEARCH after reboot. You can test this. Send the reboot() command, and while it's rebooting turn your motor, then make sure the motor returns back to the correct position each time when it comes out of reboot. Try this procedure a couple of times to be sure. ### Startup sequence notes diff --git a/tools/odrive/enums.py b/tools/odrive/enums.py index d4425a211..c5f6812ca 100644 --- a/tools/odrive/enums.py +++ b/tools/odrive/enums.py @@ -42,6 +42,7 @@ class motor: ERROR_BRAKE_DEADTIME_VIOLATION = 0x0100 ERROR_UNEXPECTED_TIMER_CALLBACK = 0x0200 ERROR_CURRENT_SENSE_SATURATION = 0x0400 + ERROR_CURRENT_UNSTABLE = 0x1000 class encoder: ERROR_NONE = 0