diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..86715075f5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,6 +71,7 @@ set(COMMON_COMPILE_DEFINITIONS include(openocd) include(svd) include(stm32) +include(at32) add_subdirectory(src) diff --git a/board/at32fc.cfg b/board/at32fc.cfg new file mode 100644 index 0000000000..aeb34d8bc7 --- /dev/null +++ b/board/at32fc.cfg @@ -0,0 +1,9 @@ +# Boardconfig for AT-LINK for AT32F4-FC + +source [find interface/atlink.cfg] + +#transport select hla_swd + +source [find target/at32f437xM.cfg] + +reset_config none separate diff --git a/cmake/at32-bootloader.cmake b/cmake/at32-bootloader.cmake new file mode 100644 index 0000000000..857ae08a52 --- /dev/null +++ b/cmake/at32-bootloader.cmake @@ -0,0 +1,33 @@ +main_sources(BOOTLOADER_SOURCES + common/log.c + common/log.h + common/printf.c + common/printf.h + common/string_light.c + common/string_light.h + common/typeconversion.c + common/typeconversion.h + + drivers/bus.c + drivers/bus_busdev_i2c.c + drivers/bus_busdev_spi.c + drivers/bus_i2c_soft.c + drivers/io.c + drivers/light_led.c + drivers/persistent.c + drivers/rcc.c + drivers/serial.c + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/flash_m25p16.c + drivers/flash_w25n01g.c + drivers/flash.c + + fc/firmware_update_common.c + fc/firmware_update_common.h + + target/common_hardware.c +) + +list(APPEND BOOTLOADER_SOURCES ${MAIN_DIR}/src/bl/bl_main.c) diff --git a/cmake/at32-stdperiph.cmake b/cmake/at32-stdperiph.cmake new file mode 100644 index 0000000000..66ef7b8852 --- /dev/null +++ b/cmake/at32-stdperiph.cmake @@ -0,0 +1,4 @@ +main_sources(AT32_STDPERIPH_SRC + drivers/bus_spi_at32f43x.c + drivers/serial_uart_hal_at32f43x.c +) diff --git a/cmake/at32.cmake b/cmake/at32.cmake new file mode 100644 index 0000000000..2722798669 --- /dev/null +++ b/cmake/at32.cmake @@ -0,0 +1,430 @@ +include(at32-bootloader) +include(at32f4) + +include(CMakeParseArguments) + +option(DEBUG_HARDFAULTS "Enable debugging of hard faults via custom handler") +option(SEMIHOSTING "Enable semihosting") + +message("-- DEBUG_HARDFAULTS: ${DEBUG_HARDFAULTS}, SEMIHOSTING: ${SEMIHOSTING}") + +set(CMSIS_DIR "${MAIN_LIB_DIR}/lib/main/AT32F43x/Drivers/CMSIS") +set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support") +# DSP use common +set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP") +set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include") + +set(CMSIS_DSP_SRC + BasicMathFunctions/arm_mult_f32.c + TransformFunctions/arm_rfft_fast_f32.c + TransformFunctions/arm_cfft_f32.c + TransformFunctions/arm_rfft_fast_init_f32.c + TransformFunctions/arm_cfft_radix8_f32.c + TransformFunctions/arm_bitreversal2.S + CommonTables/arm_common_tables.c + ComplexMathFunctions/arm_cmplx_mag_f32.c + StatisticsFunctions/arm_max_f32.c +) +list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/") + +set(AT32_STARTUP_DIR "${MAIN_SRC_DIR}/startup") + +main_sources(AT32_VCP_SRC + drivers/serial_usb_vcp_at32f43x.c + drivers/usb_io.c +) +# SDCARD not supported yet +main_sources(AT32_SDCARD_SRC + drivers/sdcard/sdcard.c + drivers/sdcard/sdcard_spi.c + drivers/sdcard/sdcard_sdio.c + drivers/sdcard/sdcard_standard.c +) + +# XXX: This code is not STM32 specific +main_sources(AT32_ASYNCFATFS_SRC + io/asyncfatfs/asyncfatfs.c + io/asyncfatfs/fat_standard.c +) + +main_sources(AT32_MSC_SRC + msc/at32_msc_diskio.c + msc/emfat.c + msc/emfat_file.c +) + +set(AT32_INCLUDE_DIRS + "${CMSIS_INCLUDE_DIR}" + "${CMSIS_DSP_INCLUDE_DIR}" + "${MAIN_SRC_DIR}/target" +) + +set(AT32_DEFINITIONS +) +set(AT32_DEFAULT_HSE_MHZ 8) +set(AT32_LINKER_DIR "${MAIN_SRC_DIR}/target/link") +set(AT32_COMPILE_OPTIONS + -ffunction-sections + -fdata-sections + -fno-common +) + +set(AT32_LINK_LIBRARIES + -lm + -lc +) + +if(SEMIHOSTING) + list(APPEND AT32_LINK_LIBRARIES --specs=rdimon.specs -lrdimon) + list(APPEND AT32_DEFINITIONS SEMIHOSTING) +else() + list(APPEND AT32_LINK_LIBRARIES -lnosys) +endif() + +set(AT32_LINK_OPTIONS + #-nostartfiles + --specs=nano.specs + -static + -Wl,-gc-sections + -Wl,-L${AT32_LINKER_DIR} + -Wl,--cref + -Wl,--no-wchar-size-warning + -Wl,--print-memory-usage +) +# Get target features +macro(get_at32_target_features output_var dir target_name) + execute_process(COMMAND "${CMAKE_C_COMPILER}" -E -dD -D${ARGV2} "${ARGV1}/target.h" + ERROR_VARIABLE _errors + RESULT_VARIABLE _result + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE _contents) + + if(NOT _result EQUAL 0) + message(FATAL_ERROR "error extracting features for AT32 target ${ARGV2}: ${_errors}") + endif() + + string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents}) + if(HAS_VCP) + list(APPEND ${ARGV0} VCP) + endif() + string(REGEX MATCH "define[\t ]+USE_FLASHFS" HAS_FLASHFS ${_contents}) + if(HAS_FLASHFS) + list(APPEND ${ARGV0} FLASHFS) + endif() + string(REGEX MATCH "define[\t ]+USE_SDCARD" HAS_SDCARD ${_contents}) + if (HAS_SDCARD) + list(APPEND ${ARGV0} SDCARD) + string(REGEX MATCH "define[\t ]+USE_SDCARD_SDIO" HAS_SDIO ${_contents}) + if (HAS_SDIO) + list(APPEND ${ARGV0} SDIO) + endif() + endif() + if(HAS_FLASHFS OR HAS_SDCARD) + list(APPEND ${ARGV0} MSC) + endif() +endmacro() + +function(get_at32_flash_size out size) + # 4: 16, 6: 32, 8: 64, B: 128, C: 256, D: 384, E: 512, F: 768, G: 1024, H: 1536, I: 2048 KiB + string(TOUPPER ${size} s) + if(${s} STREQUAL "4") + set(${out} 16 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "6") + set(${out} 32 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "B") + set(${out} 128 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "C") + set(${out} 256 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "D") + set(${out} 384 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "E") + set(${out} 512 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "F") + set(${out} 768 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "G") + set(${out} 1024 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "H") + set(${out} 1536 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "I") + set(${out} 2048 PARENT_SCOPE) + return() + endif() +endfunction() + +function(add_hex_target name exe hex) + add_custom_target(${name} ALL + cmake -E env PATH="$ENV{PATH}" + # TODO: Overriding the start address with --set-start 0x08000000 + # seems to be required due to some incorrect assumptions about .hex + # files in the configurator. Verify wether that's the case and fix + # the bug in configurator or delete this comment. + ${CMAKE_OBJCOPY} -Oihex --set-start 0x08000000 $ ${hex} + BYPRODUCTS ${hex} + ) +endfunction() + +function(add_bin_target name exe bin) + add_custom_target(${name} + cmake -E env PATH="$ENV{PATH}" + ${CMAKE_OBJCOPY} -Obinary $ ${bin} + BYPRODUCTS ${bin} + ) +endfunction() + +function(generate_map_file target) + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${target} PRIVATE "-Wl,-Map,${map}") +endfunction() + +function(set_linker_script target script) + set(script_path ${AT32_LINKER_DIR}/${args_LINKER_SCRIPT}.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${elf_target} PRIVATE -T${script_path}) +endfunction() + +function(add_at32_executable) + cmake_parse_arguments( + args + # Boolean arguments + "" + # Single value arguments + "FILENAME;NAME;OPTIMIZATION;OUTPUT_BIN_FILENAME;OUTPUT_HEX_FILENAME;OUTPUT_TARGET_NAME" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;LINKER_SCRIPT;SOURCES" + # Start parsing after the known arguments + ${ARGN} + ) + set(elf_target ${args_NAME}.elf) + add_executable(${elf_target}) + target_sources(${elf_target} PRIVATE ${args_SOURCES}) + target_include_directories(${elf_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} ${args_INCLUDE_DIRECTORIES} ${AT32_INCLUDE_DIRS}) + target_compile_definitions(${elf_target} PRIVATE ${args_COMPILE_DEFINITIONS}) + target_compile_options(${elf_target} PRIVATE ${AT32_COMPILE_OPTIONS} ${args_COMPILE_OPTIONS}) + if(WARNINGS_AS_ERRORS) + target_compile_options(${elf_target} PRIVATE -Werror) + endif() + if (IS_RELEASE_BUILD) + target_compile_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + target_link_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + endif() + target_link_libraries(${elf_target} PRIVATE ${AT32_LINK_LIBRARIES}) + target_link_options(${elf_target} PRIVATE ${AT32_LINK_OPTIONS} ${args_LINK_OPTIONS}) + generate_map_file(${elf_target}) + set_linker_script(${elf_target} ${args_LINKER_SCRIPT}) + if(args_FILENAME) + set(basename ${CMAKE_BINARY_DIR}/${args_FILENAME}) + set(hex_filename ${basename}.hex) + add_hex_target(${args_NAME} ${elf_target} ${hex_filename}) + set(bin_filename ${basename}.bin) + add_bin_target(${args_NAME}.bin ${elf_target} ${bin_filename}) + endif() + if(args_OUTPUT_BIN_FILENAME) + set(${args_OUTPUT_BIN_FILENAME} ${bin_filename} PARENT_SCOPE) + endif() + if(args_OUTPUT_TARGET_NAME) + set(${args_OUTPUT_TARGET_NAME} ${elf_target} PARENT_SCOPE) + endif() + if(args_OUTPUT_HEX_FILENAME) + set(${args_OUTPUT_HEX_FILENAME} ${hex_filename} PARENT_SCOPE) + endif() +endfunction() + +# Main function of AT32 +function(target_at32) + if(NOT arm-none-eabi STREQUAL TOOLCHAIN) + return() + endif() + # Parse keyword arguments + cmake_parse_arguments( + args + # Boolean arguments + "DISABLE_MSC;BOOTLOADER" + # Single value arguments + "HSE_MHZ;LINKER_SCRIPT;NAME;OPENOCD_TARGET;OPTIMIZATION;STARTUP;SVD" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;SOURCES;MSC_SOURCES;MSC_INCLUDE_DIRECTORIES;VCP_SOURCES;VCP_INCLUDE_DIRECTORIES" + # Start parsing after the known arguments + ${ARGN} + ) + set(name ${args_NAME}) + + if (args_HSE_MHZ) + set(hse_mhz ${args_HSE_MHZ}) + else() + set(hse_mhz ${AT32_DEFAULT_HSE_MHZ}) + endif() + + set(target_sources ${AT32_STARTUP_DIR}/${args_STARTUP}) + list(APPEND target_sources ${args_SOURCES}) + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_include_directories ${args_INCLUDE_DIRECTORIES}) + + set(target_definitions ${AT32_DEFINITIONS} ${COMMON_COMPILE_DEFINITIONS}) + + get_at32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}" ${name}) + set_property(TARGET ${elf_target} PROPERTY FEATURES ${features}) + + if(VCP IN_LIST features) + list(APPEND target_sources ${AT32_VCP_SRC} ${args_VCP_SOURCES}) + list(APPEND target_include_directories ${args_VCP_INCLUDE_DIRECTORIES}) + endif() + if(SDCARD IN_LIST features) + list(APPEND target_sources ${AT32_SDCARD_SRC} ${AT32_ASYNCFATFS_SRC}) + endif() + + set(msc_sources) + if(NOT args_DISABLE_MSC AND MSC IN_LIST features) + list(APPEND target_include_directories ${args_MSC_INCLUDE_DIRECTORIES}) + list(APPEND msc_sources ${AT32_MSC_SRC} ${args_MSC_SOURCES}) + list(APPEND target_definitions USE_USB_MSC) + if(FLASHFS IN_LIST features) + list(APPEND msc_sources ${AT32_MSC_FLASH_SRC}) + endif() + if (SDCARD IN_LIST features) + list(APPEND msc_sources ${AT32_MSC_SDCARD_SRC}) + endif() + endif() + + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + if(args_COMPILE_DEFINITIONS) + list(APPEND target_definitions ${args_COMPILE_DEFINITIONS}) + endif() + if(DEBUG_HARDFAULTS) + list(APPEND target_definitions DEBUG_HARDFAULTS) + endif() + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() + + # Main firmware + add_at32_executable( + NAME ${name} + FILENAME ${binary_name} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME main_bin_filename + OUTPUT_HEX_FILENAME main_hex_filename + OUTPUT_TARGET_NAME main_target_name + + ) + + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_TARGET ${args_OPENOCD_TARGET}) + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE atlink) + set_property(TARGET ${main_target_name} PROPERTY SVD ${args_SVD}) + + setup_firmware_target(${main_target_name} ${name} ${ARGN}) + + if(args_BOOTLOADER) + # Bootloader for the target + set(bl_suffix _bl) + add_at32_executable( + NAME ${name}${bl_suffix} + FILENAME ${binary_name}${bl_suffix} + SOURCES ${target_sources} ${BOOTLOADER_SOURCES} + COMPILE_DEFINITIONS ${target_definitions} BOOTLOADER MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME bl_bin_filename + OUTPUT_HEX_FILENAME bl_hex_filename + OUTPUT_TARGET_NAME bl_target_name + ) + setup_executable(${bl_target_name} ${name}) + + # Main firmware, but for running with the bootloader + set(for_bl_suffix _for_bl) + add_at32_executable( + NAME ${name}${for_bl_suffix} + FILENAME ${binary_name}${for_bl_suffix} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${for_bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME for_bl_bin_filename + OUTPUT_HEX_FILENAME for_bl_hex_filename + OUTPUT_TARGET_NAME for_bl_target_name + ) + setup_executable(${for_bl_target_name} ${name}) + + # Combined with bootloader and main firmware + set(with_bl_suffix _with_bl) + set(combined_hex ${CMAKE_BINARY_DIR}/${binary_name}${with_bl_suffix}.hex) + set(with_bl_target ${name}${with_bl_suffix}) + add_custom_target(${with_bl_target} + ${CMAKE_SOURCE_DIR}/src/utils/combine_tool ${bl_bin_filename} ${for_bl_bin_filename} ${combined_hex} + BYPRODUCTS ${combined_hex} + ) + add_dependencies(${with_bl_target} ${bl_target_name} ${for_bl_target_name}) + endif() + + # clean_ + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() +endfunction() diff --git a/cmake/at32f4-usb.cmake b/cmake/at32f4-usb.cmake new file mode 100644 index 0000000000..1806fcf3f0 --- /dev/null +++ b/cmake/at32f4-usb.cmake @@ -0,0 +1,45 @@ +set(AT32_USBCORE_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core") +set(AT32_USBCDC_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc") +set(AT32_USBMSC_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc") + +set(AT32F4_USB_INCLUDE_DIRS + "${AT32_USBCORE_DIR}/Inc" + "${AT32_USBCDC_DIR}" + "${AT32_USBMSC_DIR}" +) + +set(AT32_USBCORE_SRC + usb_core.c + usbd_core.c + usbd_int.c + usbd_sdr.c +) +list(TRANSFORM AT32_USBCORE_SRC PREPEND "${AT32_USBCORE_DIR}/Src/") + + +set(AT32_USBCDC_SRC + "${AT32_USBCDC_DIR}/cdc_class.c" + "${AT32_USBCDC_DIR}/cdc_desc.c" +) + +main_sources(AT32F4_VCP_SRC + drivers/serial_usb_vcp_at32f43x.c + drivers/usb_io.c +) + +set(AT32F4_USBMSC_SRC + msc_desc.c + msc_class.c + msc_bot_scsi.c +) + +main_sources(AT32F4_MSC_SRC + drivers/usb_msc_at32f43x.c +) + +list(TRANSFORM AT32F4_USBMSC_SRC PREPEND "${AT32_USBMSC_DIR}/") +list(APPEND AT32F4_USBMSC_SRC ${AT32F4_MSC_SRC}) + +list(APPEND AT32F4_USB_SRC ${AT32F4_VCP_SRC}) +list(APPEND AT32F4_USB_SRC ${AT32_USBCORE_SRC}) +list(APPEND AT32F4_USB_SRC ${AT32_USBCDC_SRC}) diff --git a/cmake/at32f4.cmake b/cmake/at32f4.cmake new file mode 100644 index 0000000000..3fb407827b --- /dev/null +++ b/cmake/at32f4.cmake @@ -0,0 +1,114 @@ +include(cortex-m4f) +include(at32-stdperiph) +include(at32f4-usb) + +set(AT32F4_STDPERIPH_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver") +set(AT32F4_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x") +set(AT32F4_CMSIS_DRIVERS_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/CMSIS") + + +set(AT32F4_STDPERIPH_SRC_EXCLUDES + at32f435_437_can.c + at32f435_437_dvp.c + at32f435_437_emac + at32f435_437_xmc.c +) + +set(AT32F4_STDPERIPH_SRC_DIR "${AT32F4_STDPERIPH_DIR}/src") +glob_except(AT32F4_STDPERIPH_SRC "${AT32F4_STDPERIPH_SRC_DIR}/*.c" "${AT32F4_STDPERIPH_SRC_EXCLUDES}") + +list(APPEND AT32F4_STDPERIPH_SRC "${AT32F4_CMSIS_DEVICE_DIR}/at32f435_437_clock.c" ) + +main_sources(AT32F4_SRC + target/system_at32f435_437.c + config/config_streamer_at32f43x.c + config/config_streamer_ram.c + config/config_streamer_extflash.c + drivers/adc_at32f43x.c + drivers/i2c_application.c + drivers/bus_i2c_at32f43x.c + drivers/bus_spi_at32f43x + drivers/serial_uart_hal_at32f43x.c + drivers/serial_uart_at32f43x.c + + drivers/system_at32f43x.c + drivers/timer.c + drivers/timer_impl_stdperiph_at32.c + drivers/timer_at32f43x.c + drivers/uart_inverter.c + drivers/dma_at32f43x.c +) + +set(AT32F4_INCLUDE_DIRS + ${CMSIS_INCLUDE_DIR} + ${CMSIS_DSP_INCLUDE_DIR} + ${AT32F4_CMSIS_DRIVERS_DIR} + ${AT32F4_STDPERIPH_DIR}/inc + ${AT32F4_CMSIS_DEVICE_DIR} + #"${AT32F4_I2C_DIR}" +) + +set(AT32F4_DEFINITIONS + ${CORTEX_M4F_DEFINITIONS} + AT32F43x + USE_STDPERIPH_DRIVER +) + +function(target_at32f43x) + target_at32( + SOURCES ${AT32_STDPERIPH_SRC} ${AT32F4_SRC} + COMPILE_DEFINITIONS ${AT32F4_DEFINITIONS} + COMPILE_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${AT32F4_INCLUDE_DIRS} + LINK_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS} + + MSC_SOURCES ${AT32F4_USBMSC_SRC} ${AT32F4_MSC_SRC} + VCP_SOURCES ${AT32F4_USB_SRC} ${AT32F4_VCP_SRC} + VCP_INCLUDE_DIRECTORIES ${AT32F4_USB_INCLUDE_DIRS} + + OPTIMIZATION -O2 + + OPENOCD_TARGET at32f437xx + + ${ARGN} + ) +endfunction() + +#target_at32f43x_xMT7 +#target_at32f43x_xGT7 + +set(at32f43x_xMT7_COMPILE_DEFINITIONS + AT32F437VMT7 + MCU_FLASH_SIZE=4032 +) + +function(target_at32f43x_xMT7 name) + target_at32f43x( + NAME ${name} + STARTUP startup_at32f435_437.s + SOURCES ${AT32F4_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${at32f43x_xMT7_COMPILE_DEFINITIONS} + LINKER_SCRIPT at32_flash_f43xM + #BOOTLOADER + SVD at32f43x_xMT7 + ${ARGN} + ) +endfunction() + +set(at32f43x_xGT7_COMPILE_DEFINITIONS + AT32F435RGT7 + MCU_FLASH_SIZE=1024 +) + +function(target_at32f43x_xGT7 name) + target_at32f43x( + NAME ${name} + STARTUP startup_at32f435_437.s + SOURCES ${AT32F4_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${at32f43x_xGT7_COMPILE_DEFINITIONS} + LINKER_SCRIPT at32_flash_f43xG + #BOOTLOADER + SVD at32f43x_xGT7 + ${ARGN} + ) +endfunction() diff --git a/dev/svd/AT32F437xx_v2.svd b/dev/svd/AT32F437xx_v2.svd new file mode 100644 index 0000000000..4f34af9d30 --- /dev/null +++ b/dev/svd/AT32F437xx_v2.svd @@ -0,0 +1,58291 @@ + + + + + + + + Keil + ArteryTek + AT32F437xx_v2 + AT32F437 + 1.0 + ARM 32-bit Cortex-M4 Microcontroller based device, CPU clock up to 288MHz, etc. + + ARM Limited (ARM) is supplying this software for use with Cortex-M\n + processor based microcontroller, but can be equally used for other\n + suitable processor architectures. This file can be freely distributed.\n + Modifications to this file shall be clearly marked.\n + \n + THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED\n + OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF\n + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.\n + ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR\n + CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + + + CM4 + r0p1 + little + false + true + 4 + false + + 8 + 32 + + 32 + read-write + 0x00000000 + 0xFFFFFFFF + + + + XMC + Flexible static memory controller + XMC + 0xA0000000 + + 0x0 + 0x1000 + registers + + + XMC + XMC global interrupt + 48 + + + + BK1CTRL1 + BK1CTRL1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030DB + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG1 + BK1TMG1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL2 + BK1CTRL2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG2 + BK1TMG2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL3 + BK1CTRL3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG3 + BK1TMG3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL4 + BK1CTRL4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG4 + BK1TMG4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK2CTRL + BK2CTRL + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPGS + ECC page size + 17 + 3 + + + TAR + ALE to RE delay + 13 + 4 + + + TCR + CLE to RE delay + 9 + 4 + + + ECCEN + ECC enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 3 + 1 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK2IS + BK2IS + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK2TMGRG + BK2TMGRG + Regular memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + RGDHIZT + Regular memory databus High resistance time + 24 + 8 + + + RGHT + Regular memory hold time + 16 + 8 + + + RGWT + Regular memory wait time + 8 + 8 + + + RGST + Regular memory setup time + 0 + 8 + + + + + BK2TMGSP + BK2TMGSP + special memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + SPDHIZT + special memory databus High resistance time + 24 + 8 + + + SPHT + special memory hold time + 16 + 8 + + + SPWT + special memory wait time + 8 + 8 + + + SPST + special memory setup time + 0 + 8 + + + + + BK2ECC + BK2ECC + ECC result register 2 + 0x74 + 0x20 + read-write + 0x00000000 + + + ECC + ECC result + 0 + 32 + + + + + BK3CTRL + BK3CTRL + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPGS + ECC page size + 17 + 3 + + + TAR + ALE to RE delay + 13 + 4 + + + TCR + CLE to RE delay + 9 + 4 + + + ECCEN + ECC enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 3 + 1 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK3IS + BK3IS + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK3TMGRG + BK3TMGRG + Regular memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + RGDHIZT + Regular memory databus High resistance time + 24 + 8 + + + RGHT + Regular memory hold time + 16 + 8 + + + RGWT + Regular memory wait time + 8 + 8 + + + RGST + Regular memory setup time + 0 + 8 + + + + + BK3TMGSP + BK3TMGSP + special memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + SPDHIZT + special memory databus High resistance time + 24 + 8 + + + SPHT + special memory hold time + 16 + 8 + + + SPWT + special memory wait time + 8 + 8 + + + SPST + special memory setup time + 0 + 8 + + + + + BK3ECC + BK3ECC + ECC result register 3 + 0x94 + 0x20 + read-write + 0x00000000 + + + ECC + ECC result + 0 + 32 + + + + + BK4CTRL + BK4CTRL + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK4IS + BK4IS + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK4TMGCM + BK4TMGCM + Regular memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + CMDHIZT + Regular memory databus High resistance time + 24 + 8 + + + CMHT + Regular memory hold time + 16 + 8 + + + CMWT + Regular memory wait time + 8 + 8 + + + CMST + Regular memory setup time + 0 + 8 + + + + + BK4TMGAT + BK4TMGAT + special memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATDHIZT + special memory databus High resistance time + 24 + 8 + + + ATHT + special memory hold time + 16 + 8 + + + ATWT + special memory wait time + 8 + 8 + + + ATST + special memory setup time + 0 + 8 + + + + + BK4TMGIO + BK4TMGIO + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IODHIZT + WRSTP + 24 + 8 + + + IOHT + HLD + 16 + 8 + + + IOWT + OP + 8 + 8 + + + IOST + STP + 0 + 8 + + + + + BK1TMGWR1 + BK1TMGWR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR2 + BK1TMGWR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR3 + BK1TMGWR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR4 + BK1TMGWR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + CTRL1 + CTRL1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + CA + Number of column address + bits + 0 + 2 + + + RA + Number of row address bits + 2 + 2 + + + DB + Memory data bus width + 4 + 2 + + + INBK + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WRP + Write protection + 9 + 1 + + + CLKDIV + Clock division configuration + 10 + 2 + + + BSTR + Burst read + 12 + 1 + + + RD + Read delay + 13 + 2 + + + + + CTRL2 + CTRL2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + CA + Number of column address + bits + 0 + 2 + + + RA + Number of row address bits + 2 + 2 + + + DB + Memory data bus width + 4 + 2 + + + INBK + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WRP + Write protection + 9 + 1 + + + CLKDIV + Clock division configuration + 10 + 2 + + + BSTR + Burst read + 12 + 1 + + + RD + Read pipe + 13 + 2 + + + + + TM1 + TM1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Mode register program to active delay + 0 + 4 + + + TXSR + Exit Self-refresh to active delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Refresh to active delay + 12 + 4 + + + TWR + Write Recovery delay + 16 + 4 + + + TRP + Precharge to active delay + 20 + 4 + + + TRCD + Row active to Read/Write delay + 24 + 4 + + + + + TM2 + TM2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Mode register program to active delay + 0 + 4 + + + TXSR + Exit Self-refresh to active delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Refresh to active delay + 12 + 4 + + + TWR + Write Recovery delay + 16 + 4 + + + TRP + Precharge to active delay + 20 + 4 + + + TRCD + Row active to Read/Write delay + 24 + 4 + + + + + CMD + CMD + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + CMD + SDRAM Command + 0 + 3 + write-only + + + BK2 + SDRAM Bank 2 + 3 + 1 + write-only + + + BK1 + SDRAM Bank 1 + 4 + 1 + write-only + + + ART + Auto-refresh times + 5 + 4 + read-write + + + MRD + Mode register data + 9 + 13 + read-write + + + + + RCNT + RCNT + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + ERRC + error flag clear + 0 + 1 + write-only + + + RC + Refresh Count + 1 + 13 + read-write + + + ERIEN + error Interrupt Enable + 14 + 1 + read-write + + + + + STS + STS + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + ERR + error flag + 0 + 1 + + + BK1STS + Bank 1 Status + 1 + 2 + + + BK2STS + Bank 2 Status + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + EXT1 + EXT1 + externl timeing register 1 + 0x220 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT2 + EXT2 + externl timeing register 2 + 0x224 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT3 + EXT3 + externl timeing register 3 + 0x228 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT4 + EXT4 + externl timeing register 4 + 0x22C + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + + + PWC + Power control + PWC + 0x40007000 + + 0x0 + 0x400 + registers + + + + CTRL + CTRL + Power control register + (PWC_CTRL) + 0x0 + 0x20 + read-write + 0x00000000 + + + VRSEL + Voltage regulator state select when deepsleep mode + 0 + 1 + + + LPSEL + Low power mode select when Cortex-M4F sleepdeep + 1 + 1 + + + CLSWEF + Clear SWEF flag + 2 + 1 + + + CLSEF + Clear SEF flag + 3 + 1 + + + PVMEN + Power voltage monitoring enable + 4 + 1 + + + PVMSEL + Power voltage monitoring boundary select + 5 + 3 + + + BPWEN + Battery powered domain write enable + 8 + 1 + + + + + CTRLSTS + CTRLSTS + Power control and status register + (PWC_CTRLSTS) + 0x4 + 0x20 + 0x00000000 + + + SWEF + Standby wake-up event flag + 0 + 1 + read-only + + + SEF + Standby mode entry flag + 1 + 1 + read-only + + + PVMOF + Power voltage monitoring output flag + 2 + 1 + read-only + + + SWPEN1 + Standby wake-up pin 1 enable + 8 + 1 + read-write + + + SWPEN2 + Standby wake-up pin 2 enable + 9 + 1 + read-write + + + + + LDOOV + LDOOV + LDO output voltage register + 0x10 + 0x20 + 0x00000000 + + + LDOOVSEL + LDO output voltage select + 0 + 3 + read-write + + + + + + + CRM + Clock and reset management + CRM + 0x40023800 + + 0x0 + 0x400 + registers + + + CRM + CRM global interrupt + 5 + + + + CTRL + CTRL + Clock control register + 0x0 + 0x20 + 0x00000083 + + + HICKEN + High speed internal clock enable + 0 + 1 + read-write + + + HICKSTBL + High speed internal clock ready flag + 1 + 1 + read-only + + + HICKTRIM + High speed internal clock trimming + 2 + 6 + read-write + + + HICKCAL + High speed internal clock calibration + 8 + 8 + read-only + + + HEXTEN + High speed exernal crystal enable + 16 + 1 + read-write + + + HEXTSTBL + High speed exernal crystal ready flag + 17 + 1 + read-only + + + HEXTBYPS + High speed exernal crystal bypass + 18 + 1 + read-write + + + CFDEN + Clock failure detection enable + 19 + 1 + read-write + + + PLLEN + PLL enable + 24 + 1 + read-write + + + PLLSTBL + PLL clock ready flag + 25 + 1 + read-only + + + + + PLLCFG + PLLCFG + PLL configuration register + (CRM_PLLCFG) + 0x4 + 0x20 + 0x00033002 + + + PLL_MS + PLL pre-division + 0 + 4 + read-write + + + PLL_NS + PLL frequency multiplication factor + 6 + 9 + read-write + + + PLL_FR + PLL post-division + 16 + 3 + read-write + + + PLLRCS + PLL reference clock select + 22 + 1 + read-write + + + + + CFG + CFG + Clock configuration register(CRM_CFG) + 0x8 + 0x20 + 0x00000000 + + + SCLKSEL + System clock select + 0 + 2 + read-write + + + SCLKSTS + System Clock select Status + 2 + 2 + read-only + + + AHBDIV + AHB division + 4 + 4 + read-write + + + APB1DIV + APB1 division + 10 + 3 + read-write + + + APB2DIV + APB2 division + 13 + 3 + read-write + + + ERTCDIV + HEXT division for ERTC clock + 16 + 5 + read-write + + + CLKOUT1_SEL + Clock output1 selection + 21 + 2 + read-write + + + CLKOUT1DIV1 + Clock output1 division1 + 24 + 3 + read-write + + + CLKOUT2DIV1 + Clock output2 division1 + 27 + 3 + read-write + + + CLKOUT2_SEL1 + Clock output2 selection1 + 30 + 2 + read-write + + + + + CLKINT + CLKINT + Clock interrupt register + (CRM_CLKINT) + 0xC + 0x20 + 0x00000000 + + + LICKSTBLF + LICK ready interrupt flag + 0 + 1 + read-only + + + LEXTSTBLF + LEXT ready interrupt flag + 1 + 1 + read-only + + + HICKSTBLF + HICK ready interrupt flag + 2 + 1 + read-only + + + HEXTSTBLF + HEXT ready interrupt flag + 3 + 1 + read-only + + + PLLSTBLF + PLL ready interrupt flag + 4 + 1 + read-only + + + CFDF + Clock failure detection interrupt flag + 7 + 1 + read-only + + + LICKSTBLIEN + LICK ready interrupt enable + 8 + 1 + read-write + + + LEXTSTBLIEN + LEXT ready interrupt enable + 9 + 1 + read-write + + + HICKSTBLIEN + HICK ready interrupt enable + 10 + 1 + read-write + + + HEXTSTBLIEN + HEXT ready interrupt enable + 11 + 1 + read-write + + + PLLSTBLIEN + PLL ready interrupt enable + 12 + 1 + read-write + + + LICKSTBLFC + LICK ready interrupt clear + 16 + 1 + write-only + + + LEXTSTBLFC + LEXT ready interrupt clear + 17 + 1 + write-only + + + HICKSTBLFC + HICK ready interrupt clear + 18 + 1 + write-only + + + HEXTSTBLFC + HEXT ready interrupt clear + 19 + 1 + write-only + + + PLLSTBLFC + PLL ready interrupt clear + 20 + 1 + write-only + + + CFDFC + Clock failure detection interrupt clear + 23 + 1 + write-only + + + + + AHBRST1 + AHBRST1 + AHB peripheral reset register1 + (CRM_AHBRST1) + 0x10 + 0x20 + read-write + 0x000000000 + + + GPIOARST + IO port A reset + 0 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + EDMARST + EDMA reset + 21 + 1 + + + DMA1RST + DMA1 reset + 22 + 1 + + + DMA2RST + DMA2 reset + 24 + 1 + + + EMACRST + EMAC reset + 25 + 1 + + + OTGFS2RST + OTGFS2 interface reset + 29 + 1 + + + + + AHBRST2 + AHBRST2 + AHB peripheral reset register 2 + (CRM_AHBRST2) + 0x14 + 0x20 + read-write + 0x00000000 + + + DVPRST + DVP reset + 0 + 1 + + + OTGFS1RST + OTGFS1 reset + 7 + 1 + + + SDIO1RST + SDIO1 reset + 15 + 1 + + + + + AHBRST3 + AHBRST3 + AHB peripheral reset register 3 + (CRM_AHBRST3) + 0x18 + 0x20 + read-write + 0x00000000 + + + XMCRST + XMC reset + 0 + 1 + + + QSPI1RST + QSPI1 reset + 1 + 1 + + + QSPI2RST + QSPI2 reset + 14 + 1 + + + SDIO2RST + SDIO2 reset + 15 + 1 + + + + + APB1RST + APB1RST + APB1 peripheral reset register + (CRM_APB1RST) + 0x20 + 0x20 + read-write + 0x00000000 + + + TMR2RST + Timer2 reset + 0 + 1 + + + TMR3RST + Timer3 reset + 1 + 1 + + + TMR4RST + Timer4 reset + 2 + 1 + + + TMR5RST + Timer5 reset + 3 + 1 + + + TMR6RST + Timer6 reset + 4 + 1 + + + TMR7RST + Timer7 reset + 5 + 1 + + + TMR12RST + Timer12 reset + 6 + 1 + + + TMR13RST + Timer13 reset + 7 + 1 + + + TMR14RST + Timer14 reset + 8 + 1 + + + WWDTRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI2 reset + 14 + 1 + + + SPI3RST + SPI3 reset + 15 + 1 + + + USART2RST + USART2 reset + 17 + 1 + + + USART3RST + USART3 reset + 18 + 1 + + + UART4RST + UART4 reset + 19 + 1 + + + UART5RST + UART5 reset + 20 + 1 + + + I2C1RST + I2C1 reset + 21 + 1 + + + I2C2RST + I2C2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWCRST + PWC reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + + + APB2RST + APB2RST + APB2 peripheral reset register + (CRM_APB2RST) + 0x24 + 0x20 + read-write + 0x00000000 + + + TMR1RST + Timer1 reset + 0 + 1 + + + TMR8RST + Timer8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC reset + 8 + 1 + + + SPI1RST + SPI1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SCFGRST + SCFG reset + 14 + 1 + + + TMR9RST + Timer9 reset + 16 + 1 + + + TMR10RST + Timer10 reset + 17 + 1 + + + TMR11RST + Timer 11 reset + 18 + 1 + + + TMR20RST + Timer20 reset + 20 + 1 + + + ACCRST + ACC reset + 29 + 1 + + + + + AHBEN1 + AHBEN1 + AHB Peripheral Clock enable register 1 + (CRM_AHBEN1) + 0x30 + 0x20 + read-write + 0x00000000 + + + GPIOAEN + IO A clock enable + 0 + 1 + + + GPIOBEN + IO B clock enable + 1 + 1 + + + GPIOCEN + IO C clock enable + 2 + 1 + + + GPIODEN + IO D clock enable + 3 + 1 + + + GPIOEEN + IO E clock enable + 4 + 1 + + + GPIOFEN + IO F clock enable + 5 + 1 + + + GPIOGEN + IO G clock enable + 6 + 1 + + + GPIOHEN + IO H clock enable + 7 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + EDMAEN + DMA1 clock enable + 21 + 1 + + + DMA1EN + DMA1 clock enable + 22 + 1 + + + DMA2EN + DMA2 clock enable + 24 + 1 + + + EMACEN + EMAC clock enable + 25 + 1 + + + EMACTXEN + EMAC Tx clock enable + 26 + 1 + + + EMACRXEN + EMAC Rx clock enable + 27 + 1 + + + EMACPTPEN + EMAC PTP clock enable + 28 + 1 + + + OTGFS2EN + OTGFS2 clock enable + 29 + 1 + + + + + AHBEN2 + AHBEN2 + AHB peripheral clock enable register 2 + (CRM_AHBEN2) + 0x34 + 0x20 + read-write + 0x00000000 + + + DVPEN + DVP clock enable + 0 + 1 + + + OTGFS1EN + OTGFS1 clock enable + 7 + 1 + + + SDIO1EN + SDIO1 clock enable + 15 + 1 + + + + + AHBEN3 + AHBEN3 + AHB peripheral clock enable register 3 + (CRM_AHBEN3) + 0x38 + 0x20 + read-write + 0x00000000 + + + XMCEN + XMC clock enable + 0 + 1 + + + QSPI1EN + QSPI1 clock enable + 1 + 1 + + + QSPI2EN + QSPI2 clock enable + 14 + 1 + + + SDIO2EN + SDIO 2 clock enable + 15 + 1 + + + + + APB1EN + APB1EN + APB1 peripheral clock enable register + (CRM_APB1EN) + 0x40 + 0x20 + read-write + 0x00000000 + + + TMR2EN + Timer2 clock enable + 0 + 1 + + + TMR3EN + Timer3 clock enable + 1 + 1 + + + TMR4EN + Timer4 clock enable + 2 + 1 + + + TMR5EN + Timer5 clock enable + 3 + 1 + + + TMR6EN + Timer6 clock enable + 4 + 1 + + + TMR7EN + Timer7 clock enable + 5 + 1 + + + TMR12EN + Timer12 clock enable + 6 + 1 + + + TMR13EN + Timer13 clock enable + 7 + 1 + + + TMR14EN + Timer14 clock enable + 8 + 1 + + + WWDTEN + WWDT clock enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN1 clock enable + 25 + 1 + + + CAN2EN + CAN2 clock enable + 26 + 1 + + + PWCEN + PWC clock enable + 28 + 1 + + + DACEN + DAC clock enable + 29 + 1 + + + UART7EN + UART7 clock enable + 30 + 1 + + + UART8EN + UART8 clock enable + 31 + 1 + + + + + APB2EN + APB2EN + APB2 peripheral clock enable register + (CRM_APB2EN) + 0x44 + 0x20 + read-write + 0x00000000 + + + TMR1EN + Timer1 clock enable + 0 + 1 + + + TMR8EN + Timer8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4EN + SPI4 clock enable + 13 + 1 + + + SCFGEN + SCFG clock enable + 14 + 1 + + + TMR9EN + Timer9 clock enable + 16 + 1 + + + TMR10EN + Timer10 clock enable + 17 + 1 + + + TMR11EN + Timer11 clock enable + 18 + 1 + + + TMR20EN + Timer20 clock enable + 20 + 1 + + + ACCEN + ACC clock enable + 29 + 1 + + + + + AHBLPEN1 + AHBLPEN1 + AHB Low-power Peripheral Clock enable + register 1 (CRM_AHBLPEN1) + 0x50 + 0x20 + read-write + 0x3E6390FF + + + GPIOALPEN + IO A clock enable during sleep mode + 0 + 1 + + + GPIOBLPEN + IO B clock enable during sleep mode + 1 + 1 + + + GPIOCLPEN + IO C clock enable during sleep mode + 2 + 1 + + + GPIODLPEN + IO D clock enable during sleep mode + 3 + 1 + + + GPIOELPEN + IO E clock enable during sleep mode + 4 + 1 + + + GPIOFLPEN + IO F clock enable during sleep mode + 5 + 1 + + + GPIOGLPEN + IO G clock enable during sleep mode + 6 + 1 + + + GPIOHLPEN + IO H clock enable during sleep mode + 7 + 1 + + + CRCLPEN + CRC clock enable during sleep mode + 12 + 1 + + + FLASHLPEN + Flash clock enable during sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM1 clock enable during sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM2 clock enable during sleep mode + 17 + 1 + + + EDMALPEN + EDMA clock enable during sleep mode + 21 + 1 + + + DMA1LPEN + DMA1 clock enable during sleep mode + 22 + 1 + + + DMA2LPEN + DMA2 clock enable during sleep mode + 24 + 1 + + + EMACLPEN + EMAC clock enable during sleep mode + 25 + 1 + + + EMACTXLPEN + EMAC Tx clock enable during sleep mode + 26 + 1 + + + EMACRXLPEN + EMAC Rx clock enable during sleep mode + 27 + 1 + + + EMACPTPLPEN + EMAC PTP clock enable during sleep mode + 28 + 1 + + + OTGFS2LPEN + OTGFS2 clock enable during sleep mode + 29 + 1 + + + + + AHBLPEN2 + AHBLPEN2 + AHB peripheral Low-power clock + enable register 2 (CRM_AHBLPEN2) + 0x54 + 0x20 + read-write + 0x00008081 + + + DVPLPEN + DVP clock enable during sleep mode + 0 + 1 + + + OTGFS1LPEN + OTGFS1 clock enable during sleep mode + 7 + 1 + + + SDIO1LPEN + SDIO1 clock enable during sleep mode + 15 + 1 + + + + + AHBLPEN3 + AHBLPEN3 + AHB peripheral Low-power clock + enable register 3 (CRM_AHBLPEN3) + 0x58 + 0x20 + read-write + 0x0000C003 + + + XMCLPEN + XMC clock enable during sleep mode + 0 + 1 + + + QSPI1LPEN + QSPI1 clock enable during sleep mode + 1 + 1 + + + QSPI2LPEN + QSPI2 clock enable during sleep mode + 14 + 1 + + + SDIO2LPEN + SDIO2 clock enable during sleep mode + 15 + 1 + + + + + APB1LPEN + APB1LPEN + APB1 peripheral Low-power clock + enable register (CRM_APB1LPEN) + 0x60 + 0x20 + read-write + 0xF6FEE9FF + + + TMR2LPEN + Timer2 clock enable during sleep mode + 0 + 1 + + + TMR3LPEN + Timer3 clock enable during sleep mode + 1 + 1 + + + TMR4LPEN + Timer4 clock enable during sleep mode + 2 + 1 + + + TMR5LPEN + Timer5 clock enable during sleep mode + 3 + 1 + + + TMR6LPEN + Timer6 clock enable during sleep mode + 4 + 1 + + + TMR7LPEN + Timer7 clock enable during sleep mode + 5 + 1 + + + TMR12LPEN + Timer12 clock enable during sleep mode + 6 + 1 + + + TMR13LPEN + Timer13 clock enable during sleep mode + 7 + 1 + + + TMR14LPEN + Timer14 clock enable during sleep mode + 8 + 1 + + + WWDTLPEN + WWDT clock enable during sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during sleep mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during sleep mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during sleep mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during sleep mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during sleep mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during sleep mode + 20 + 1 + + + I2C1CPEN + I2C1 clock enable during sleep mode + 21 + 1 + + + I2C2CPEN + I2C2 clock enable during sleep mode + 22 + 1 + + + I2C3CPEN + I2C3 clock enable during sleep mode + 23 + 1 + + + CAN1LPEN + CAN1 clock enable during sleep mode + 25 + 1 + + + CAN2LPEN + CAN2 clock enable during sleep mode + 26 + 1 + + + PWCLPEN + PWC clock enable during sleep mode + 28 + 1 + + + DACLPEN + DAC clock enable during sleep mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during sleep mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during sleep mode + 31 + 1 + + + + + APB2LPEN + APB2LPEN + APB2 peripheral Low-power clock + enable register (CRM_APB2LPEN) + 0x64 + 0x20 + read-write + 0x20177733 + + + TMR1LPEN + Timer1 clock enable during sleep mode + 0 + 1 + + + TMR8LPEN + Timer8 clock enable during sleep mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during sleep mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during sleep mode + 5 + 1 + + + ADC1CPEN + ADC1 clock enable during sleep mode + 8 + 1 + + + ADC2CPEN + ADC2 clock enable during sleep mode + 9 + 1 + + + ADC3EN + ADC3 clock enable during sleep mode + 10 + 1 + + + SPI1LPEN + SPI1 clock enable during sleep mode + 12 + 1 + + + SPI4LPEN + SPI4 clock enable during sleep mode + 13 + 1 + + + SCFGLPEN + SCFG clock enable during sleep mode + 14 + 1 + + + TMR9LPEN + Timer9 clock enable during sleep mode + 16 + 1 + + + TMR10LPEN + Timer10 clock enable during sleep mode + 17 + 1 + + + TMR11LPEN + Timer11 clock enable during sleep mode + 18 + 1 + + + TMR20LPEN + Timer20 clock enable during sleep mode + 20 + 1 + + + ACCLPEN + ACC clock enable during sleep mode + 29 + 1 + + + + + BPDC + BPDC + Battery powered domain control register + (CRM_BPDC) + 0x70 + 0x20 + 0x00000000 + + + LEXTEN + Low speed external crystal enable + 0 + 1 + read-write + + + LEXTSTBL + Low speed external crystal ready + 1 + 1 + read-only + + + LEXTBYPS + Low speed external crystal bypass + 2 + 1 + read-write + + + ERTCSEL + ERTC clock source selection + 8 + 2 + read-write + + + ERTCEN + ERTC clock enable + 15 + 1 + read-write + + + BPDRST + Battery powered domain software reset + 16 + 1 + read-write + + + + + CTRLSTS + CTRLSTS + Control/status register + (CRM_CTRLSTS) + 0x74 + 0x20 + 0x0C000000 + + + LICKEN + Low speed internal clock enable + 0 + 1 + read-write + + + LICKSTBL + Low speed internal clock ready + 1 + 1 + read-only + + + RSTFC + Reset reset flag + 24 + 1 + read-write + + + NRSTF + PIN reset flag + 26 + 1 + read-write + + + PORRSTF + POR/LVR reset flag + 27 + 1 + read-write + + + SWRSTF + Software reset flag + 28 + 1 + read-write + + + WDTRSTF + Watchdog timer reset flag + 29 + 1 + read-write + + + WWDTRSTF + Window watchdog timer reset flag + 30 + 1 + read-write + + + LPRSTF + Low-power reset flag + 31 + 1 + read-write + + + + + MISC1 + MISC1 + Miscellaneous register1 + 0xA0 + 0x20 + 0x00000000 + + + HICKCAL_KEY + HICKCAL write key value + 0 + 8 + read-write + + + HICKDIV + HICK 6 divider selection + 12 + 1 + read-write + + + HICK_TO_USB + HICK to usb clock + 13 + 1 + read-write + + + HICK_TO_SCLK + HICK to system clock + 14 + 1 + read-write + + + CLKOUT2_SEL2 + Clock output2 select2 + 16 + 4 + read-write + + + CLKOUT1DIV2 + Clock output1 division2 + 24 + 4 + read-write + + + CLKOUT2DIV2 + Clock output2 division2 + 28 + 4 + read-write + + + + + MISC2 + MISC2 + Miscellaneous register2 + 0xA4 + 0x20 + 0x0000000D + + + AUTO_STEP_EN + AUTO_STEP_EN + 4 + 2 + read-write + + + CLK_TO_TMR + Clock output internal connect to timer10 + 8 + 1 + read-write + + + USBDIV + USB division + 12 + 4 + read-write + + + + + + + GPIOA + General purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + CFGR + CFGR + GPIO configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + IOMC15 + GPIOx pin 15 mode configurate + 30 + 2 + + + IOMC14 + GPIOx pin 14 mode configurate + 28 + 2 + + + IOMC13 + GPIOx pin 13 mode configurate + 26 + 2 + + + IOMC12 + GPIOx pin 12 mode configurate + 24 + 2 + + + IOMC11 + GPIOx pin 11 mode configurate + 22 + 2 + + + IOMC10 + GPIOx pin 10 mode configurate + 20 + 2 + + + IOMC9 + GPIOx pin 9 mode configurate + 18 + 2 + + + IOMC8 + GPIOx pin 8 mode configurate + 16 + 2 + + + IOMC7 + GPIOx pin 7 mode configurate + 14 + 2 + + + IOMC6 + GPIOx pin 6 mode configurate + 12 + 2 + + + IOMC5 + GPIOx pin 5 mode configurate + 10 + 2 + + + IOMC4 + GPIOx pin 4 mode configurate + 8 + 2 + + + IOMC3 + GPIOx pin 3 mode configurate + 6 + 2 + + + IOMC2 + GPIOx pin 2 mode configurate + 4 + 2 + + + IOMC1 + GPIOx pin 1 mode configurate + 2 + 2 + + + IOMC0 + GPIOx pin 0 mode configurate + 0 + 2 + + + + + OMODE + OMODE + GPIO output mode register + 0x4 + 0x20 + read-write + 0x00000000 + + + OM15 + GPIOx pin 15 outpu mode configurate + 15 + 1 + + + OM14 + GPIOx pin 14 outpu mode configurate + 14 + 1 + + + OM13 + GPIOx pin 13 outpu mode configurate + 13 + 1 + + + OM12 + GPIOx pin 12 outpu mode configurate + 12 + 1 + + + OM11 + GPIOx pin 11 outpu mode configurate + 11 + 1 + + + OM10 + GPIOx pin 10 outpu mode configurate + 10 + 1 + + + OM9 + GPIOx pin 9 outpu mode configurate + 9 + 1 + + + OM8 + GPIOx pin 8 outpu mode configurate + 8 + 1 + + + OM7 + GPIOx pin 7 outpu mode configurate + 7 + 1 + + + OM6 + GPIOx pin 6 outpu mode configurate + 6 + 1 + + + OM5 + GPIOx pin 5 outpu mode configurate + 5 + 1 + + + OM4 + GPIOx pin 4 outpu mode configurate + 4 + 1 + + + OM3 + GPIOx pin 3 outpu mode configurate + 3 + 1 + + + OM2 + GPIOx pin 2 outpu mode configurate + 2 + 1 + + + OM1 + GPIOx pin 1 outpu mode configurate + 1 + 1 + + + OM0 + GPIOx pin 0 outpu mode configurate + 0 + 1 + + + + + ODRVR + ODRVR + GPIO drive capability register + 0x8 + 0x20 + read-write + 0x00000000 + + + ODRV15 + GPIOx pin 15 output drive capability + 30 + 2 + + + ODRV14 + GPIOx pin 14 output drive capability + 28 + 2 + + + ODRV13 + GPIOx pin 13 output drive capability + 26 + 2 + + + ODRV12 + GPIOx pin 12 output drive capability + 24 + 2 + + + ODRV11 + GPIOx pin 11 output drive capability + 22 + 2 + + + ODRV10 + GPIOx pin 10 output drive capability + 20 + 2 + + + ODRV9 + GPIOx pin 9 output drive capability + 18 + 2 + + + ODRV8 + GPIOx pin 8 output drive capability + 16 + 2 + + + ODRV7 + GPIOx pin 7 output drive capability + 14 + 2 + + + ODRV6 + GPIOx pin 6 output drive capability + 12 + 2 + + + ODRV5 + GPIOx pin 5 output drive capability + 10 + 2 + + + ODRV4 + GPIOx pin 4 output drive capability + 8 + 2 + + + ODRV3 + GPIOx pin 3 output drive capability + 6 + 2 + + + ODRV2 + GPIOx pin 2 output drive capability + 4 + 2 + + + ODRV1 + GPIOx pin 1 output drive capability + 2 + 2 + + + ODRV0 + GPIOx pin 0 output drive capability + 0 + 2 + + + + + PULL + PULL + GPIO pull-up/pull-down register + 0xC + 0x20 + read-write + 0x00000000 + + + PULL15 + GPIOx pin 15 pull configuration + 30 + 2 + + + PULL14 + GPIOx pin 14 pull configuration + 28 + 2 + + + PULL13 + GPIOx pin 13 pull configuration + 26 + 2 + + + PULL12 + GPIOx pin 12 pull configuration + 24 + 2 + + + PULL11 + GPIOx pin 11 pull configuration + 22 + 2 + + + PULL10 + GPIOx pin 10 pull configuration + 20 + 2 + + + PULL9 + GPIOx pin 9 pull configuration + 18 + 2 + + + PULL8 + GPIOx pin 8 pull configuration + 16 + 2 + + + PULL7 + GPIOx pin 7 pull configuration + 14 + 2 + + + PULL6 + GPIOx pin 6 pull configuration + 12 + 2 + + + PULL5 + GPIOx pin 5 pull configuration + 10 + 2 + + + PULL4 + GPIOx pin 4 pull configuration + 8 + 2 + + + PULL3 + GPIOx pin 3 pull configuration + 6 + 2 + + + PULL2 + GPIOx pin 2 pull configuration + 4 + 2 + + + PULL1 + GPIOx pin 1 pull configuration + 2 + 2 + + + PULL0 + GPIOx pin 0 pull configuration + 0 + 2 + + + + + IDT + IDT + GPIO input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDT0 + Port input data + 0 + 1 + + + IDT1 + Port input data + 1 + 1 + + + IDT2 + Port input data + 2 + 1 + + + IDT3 + Port input data + 3 + 1 + + + IDT4 + Port input data + 4 + 1 + + + IDT5 + Port input data + 5 + 1 + + + IDT6 + Port input data + 6 + 1 + + + IDT7 + Port input data + 7 + 1 + + + IDT8 + Port input data + 8 + 1 + + + IDT9 + Port input data + 9 + 1 + + + IDT10 + Port input data + 10 + 1 + + + IDT11 + Port input data + 11 + 1 + + + IDT12 + Port input data + 12 + 1 + + + IDT13 + Port input data + 13 + 1 + + + IDT14 + Port input data + 14 + 1 + + + IDT15 + Port input data + 15 + 1 + + + + + ODT + ODT + GPIO output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODT0 + Port output data + 0 + 1 + + + ODT1 + Port output data + 1 + 1 + + + ODT2 + Port output data + 2 + 1 + + + ODT3 + Port output data + 3 + 1 + + + ODT4 + Port output data + 4 + 1 + + + ODT5 + Port output data + 5 + 1 + + + ODT6 + Port output data + 6 + 1 + + + ODT7 + Port output data + 7 + 1 + + + ODT8 + Port output data + 8 + 1 + + + ODT9 + Port output data + 9 + 1 + + + ODT10 + Port output data + 10 + 1 + + + ODT11 + Port output data + 11 + 1 + + + ODT12 + Port output data + 12 + 1 + + + ODT13 + Port output data + 13 + 1 + + + ODT14 + Port output data + 14 + 1 + + + ODT15 + Port output data + 15 + 1 + + + + + SCR + SCR + Port bit set/clear register + 0x18 + 0x20 + write-only + 0x00000000 + + + IOSB0 + Set bit 0 + 0 + 1 + + + IOSB1 + Set bit 1 + 1 + 1 + + + IOSB2 + Set bit 1 + 2 + 1 + + + IOSB3 + Set bit 3 + 3 + 1 + + + IOSB4 + Set bit 4 + 4 + 1 + + + IOSB5 + Set bit 5 + 5 + 1 + + + IOSB6 + Set bit 6 + 6 + 1 + + + IOSB7 + Set bit 7 + 7 + 1 + + + IOSB8 + Set bit 8 + 8 + 1 + + + IOSB9 + Set bit 9 + 9 + 1 + + + IOSB10 + Set bit 10 + 10 + 1 + + + IOSB11 + Set bit 11 + 11 + 1 + + + IOSB12 + Set bit 12 + 12 + 1 + + + IOSB13 + Set bit 13 + 13 + 1 + + + IOSB14 + Set bit 14 + 14 + 1 + + + IOSB15 + Set bit 15 + 15 + 1 + + + IOCB0 + Clear bit 0 + 16 + 1 + + + IOCB1 + Clear bit 1 + 17 + 1 + + + IOCB2 + Clear bit 2 + 18 + 1 + + + IOCB3 + Clear bit 3 + 19 + 1 + + + IOCB4 + Clear bit 4 + 20 + 1 + + + IOCB5 + Clear bit 5 + 21 + 1 + + + IOCB6 + Clear bit 6 + 22 + 1 + + + IOCB7 + Clear bit 7 + 23 + 1 + + + IOCB8 + Clear bit 8 + 24 + 1 + + + IOCB9 + Clear bit 9 + 25 + 1 + + + IOCB10 + Clear bit 10 + 26 + 1 + + + IOCB11 + Clear bit 11 + 27 + 1 + + + IOCB12 + Clear bit 12 + 28 + 1 + + + IOCB13 + Clear bit 13 + 29 + 1 + + + IOCB14 + Clear bit 14 + 30 + 1 + + + IOCB15 + Clear bit 15 + 31 + 1 + + + + + WPR + WPR + Port write protect + register + 0x1C + 0x20 + read-write + 0x00000000 + + + WPEN0 + Write protect enable 0 + 0 + 1 + + + WPEN1 + Write protect enable 1 + 1 + 1 + + + WPEN2 + Write protect enable 2 + 2 + 1 + + + WPEN3 + Write protect enable 3 + 3 + 1 + + + WPEN4 + Write protect enable 4 + 4 + 1 + + + WPEN5 + Write protect enable 5 + 5 + 1 + + + WPEN6 + Write protect enable 6 + 6 + 1 + + + WPEN7 + Write protect enable 7 + 7 + 1 + + + WPEN8 + Write protect enable 8 + 8 + 1 + + + WPEN9 + Write protect enable 9 + 9 + 1 + + + WPEN10 + Write protect enable 10 + 10 + 1 + + + WPEN11 + Write protect enable 11 + 11 + 1 + + + WPEN12 + Write protect enable 12 + 12 + 1 + + + WPEN13 + Write protect enable 13 + 13 + 1 + + + WPEN14 + Write protect enable 14 + 14 + 1 + + + WPEN15 + Write protect enable 15 + 15 + 1 + + + WPSEQ + Write protect sequence + 16 + 1 + + + + + MUXL + MUXL + GPIO muxing function low register + 0x20 + 0x20 + read-write + 0x00000000 + + + MUXL7 + GPIOx pin 7 muxing + 28 + 4 + + + MUXL6 + GPIOx pin 6 muxing + 24 + 4 + + + MUXL5 + GPIOx pin 5 muxing + 20 + 4 + + + MUXL4 + GPIOx pin 4 muxing + 16 + 4 + + + MUXL3 + GPIOx pin 3 muxing + 12 + 4 + + + MUXL2 + GPIOx pin 2 muxing + 8 + 4 + + + MUXL1 + GPIOx pin 1 muxing + 4 + 4 + + + MUXL0 + GPIOx pin 0 muxing + 0 + 4 + + + + + MUXH + MUXH + GPIO muxing function high register + 0x24 + 0x20 + read-write + 0x00000000 + + + MUXH15 + GPIOx pin 15 muxing + 28 + 4 + + + MUXH14 + GPIOx pin 14 muxing + 24 + 4 + + + MUXH13 + GPIOx pin 13 muxing + 20 + 4 + + + MUXH12 + GPIOx pin 12 muxing + 16 + 4 + + + MUXH11 + GPIOx pin 11 muxing + 12 + 4 + + + MUXH10 + GPIOx pin 10 muxing + 8 + 4 + + + MUXH9 + GPIOx pin 9 muxing + 4 + 4 + + + MUXH8 + GPIOx pin 8 muxing + 0 + 4 + + + + + CLR + CLR + GPIO bit reset register + 0x28 + 0x20 + write-only + 0x00000000 + + + IOCB0 + Clear bit 0 + 0 + 1 + + + IOCB1 + Clear bit 1 + 1 + 1 + + + IOCB2 + Clear bit 1 + 2 + 1 + + + IOCB3 + Clear bit 3 + 3 + 1 + + + IOCB4 + Clear bit 4 + 4 + 1 + + + IOCB5 + Clear bit 5 + 5 + 1 + + + IOCB6 + Clear bit 6 + 6 + 1 + + + IOCB7 + Clear bit 7 + 7 + 1 + + + IOCB8 + Clear bit 8 + 8 + 1 + + + IOCB9 + Clear bit 9 + 9 + 1 + + + IOCB10 + Clear bit 10 + 10 + 1 + + + IOCB11 + Clear bit 11 + 11 + 1 + + + IOCB12 + Clear bit 12 + 12 + 1 + + + IOCB13 + Clear bit 13 + 13 + 1 + + + IOCB14 + Clear bit 14 + 14 + 1 + + + IOCB15 + Clear bit 15 + 15 + 1 + + + + + HDRV + HDRV + Huge current driver + 0x3C + 0x20 + read-write + 0x00000000 + + + HDRV0 + Port x driver bit y + 0 + 1 + + + HDRV1 + Port x driver bit y + 1 + 1 + + + HDRV2 + Port x driver bit y + 2 + 1 + + + HDRV3 + Port x driver bit y + 3 + 1 + + + HDRV4 + Port x driver bit y + 4 + 1 + + + HDRV5 + Port x driver bit y + 5 + 1 + + + HDRV6 + Port x driver bit y + 6 + 1 + + + HDRV7 + Port x driver bit y + 7 + 1 + + + HDRV8 + Port x driver bit y + 8 + 1 + + + HDRV9 + Port x driver bit y + 9 + 1 + + + HDRV10 + Port x driver bit y + 10 + 1 + + + HDRV11 + Port x driver bit y + 11 + 1 + + + HDRV12 + Port x driver bit y + 12 + 1 + + + HDRV13 + Port x driver bit y + 13 + 1 + + + HDRV14 + Port x driver bit y + 14 + 1 + + + HDRV15 + Port x driver bit y + 15 + 1 + + + + + + + GPIOB + 0x40020400 + + + GPIOC + 0x40020800 + + + GPIOD + 0x40020C00 + + + GPIOE + 0x40021000 + + + GPIOF + 0x40021400 + + + GPIOG + 0x40021800 + + + GPIOH + 0x40021C00 + + + EXINT + EXINT + EXINT + 0x40013C00 + + 0x0 + 0x400 + registers + + + EXINT0 + EXINT Line0 interrupt + 6 + + + EXINT1 + EXINT Line1 interrupt + 7 + + + EXINT2 + EXINT Line2 interrupt + 8 + + + EXINT3 + EXINT Line3 interrupt + 9 + + + EXINT4 + EXINT Line4 interrupt + 10 + + + EXINT9_5 + EXINT Line[9:5] interrupts + 23 + + + EXINT15_10 + EXINT Line[15:10] interrupts + 40 + + + PVM + PVM interrupt connect to EXINT line16 + 1 + + + ERTCALARM + ERTC Alarm interrupt connect to EXINT line17 + 41 + + + OTGFS1_WKUP + OTGFS1_WKUP interrupt connect to EXINT line18 + 42 + + + EMAC_WKUP + EMAC_WKUP interrupt connect to EXINT line19 + 62 + + + OTGFS2_WKUP + OTGFS2_WKUP interrupt connect to EXINT line20 + 76 + + + TAMPER + Tamper interrupt connect to EXINT line21 + 2 + + + ERTC_WKUP + ERTC Global interrupt connect to EXINT line22 + 3 + + + + INTEN + INTEN + Interrupt enable register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTEN0 + Interrupt enable or disable on line 0 + 0 + 1 + + + INTEN1 + Interrupt enable or disable on line 1 + 1 + 1 + + + INTEN2 + Interrupt enable or disable on line 2 + 2 + 1 + + + INTEN3 + Interrupt enable or disable on line 3 + 3 + 1 + + + INTEN4 + Interrupt enable or disable on line 4 + 4 + 1 + + + INTEN5 + Interrupt enable or disable on line 5 + 5 + 1 + + + INTEN6 + Interrupt enable or disable on line 6 + 6 + 1 + + + INTEN7 + Interrupt enable or disable on line 7 + 7 + 1 + + + INTEN8 + Interrupt enable or disable on line 8 + 8 + 1 + + + INTEN9 + Interrupt enable or disable on line 9 + 9 + 1 + + + INTEN10 + Interrupt enable or disable on line 10 + 10 + 1 + + + INTEN11 + Interrupt enable or disable on line 11 + 11 + 1 + + + INTEN12 + Interrupt enable or disable on line 12 + 12 + 1 + + + INTEN13 + Interrupt enable or disable on line 13 + 13 + 1 + + + INTEN14 + Interrupt enable or disable on line 14 + 14 + 1 + + + INTEN15 + Interrupt enable or disable on line 15 + 15 + 1 + + + INTEN16 + Interrupt enable or disable on line 16 + 16 + 1 + + + INTEN17 + Interrupt enable or disable on line 17 + 17 + 1 + + + INTEN18 + Interrupt enable or disable on line 18 + 18 + 1 + + + INTEN19 + Interrupt enable or disable on line 19 + 19 + 1 + + + INTEN20 + Interrupt enable or disable on line 20 + 20 + 1 + + + INTEN21 + Interrupt enable or disable on line 21 + 21 + 1 + + + INTEN22 + Interrupt enable or disable on line 22 + 22 + 1 + + + + + EVTEN + EVTEN + Event enable register + 0x4 + 0x20 + read-write + 0x00000000 + + + EVTEN0 + Event enable or disable on line 0 + 0 + 1 + + + EVTEN1 + Event enable or disable on line 1 + 1 + 1 + + + EVTEN2 + Event enable or disable on line 2 + 2 + 1 + + + EVTEN3 + Event enable or disable on line 3 + 3 + 1 + + + EVTEN4 + Event enable or disable on line 4 + 4 + 1 + + + EVTEN5 + Event enable or disable on line 5 + 5 + 1 + + + EVTEN6 + Event enable or disable on line 6 + 6 + 1 + + + EVTEN7 + Event enable or disable on line 7 + 7 + 1 + + + EVTEN8 + Event enable or disable on line 8 + 8 + 1 + + + EVTEN9 + Event enable or disable on line 9 + 9 + 1 + + + EVTEN10 + Event enable or disable on line 10 + 10 + 1 + + + EVTEN11 + Event enable or disable on line 11 + 11 + 1 + + + EVTEN12 + Event enable or disable on line 12 + 12 + 1 + + + EVTEN13 + Event enable or disable on line 13 + 13 + 1 + + + EVTEN14 + Event enable or disable on line 14 + 14 + 1 + + + EVTEN15 + Event enable or disable on line 15 + 15 + 1 + + + EVTEN16 + Event enable or disable on line 16 + 16 + 1 + + + EVTEN17 + Event enable or disable on line 17 + 17 + 1 + + + EVTEN18 + Event enable or disable on line 18 + 18 + 1 + + + EVTEN19 + Event enable or disable on line 19 + 19 + 1 + + + EVTEN20 + Event enable or disable on line 20 + 20 + 1 + + + EVTEN21 + Event enable or disable on line 21 + 21 + 1 + + + EVTEN22 + Event enable or disable on line 22 + 22 + 1 + + + + + POLCFG1 + POLCFG1 + Rising polarity configuration register + 0x8 + 0x20 + read-write + 0x00000000 + + + RP0 + Rising polarity configuration bit of line 0 + 0 + 1 + + + RP1 + Rising polarity configuration bit of line 1 + 1 + 1 + + + RP2 + Rising polarity configuration bit of line 2 + 2 + 1 + + + RP3 + Rising polarity configuration bit of line 3 + 3 + 1 + + + RP4 + Rising polarity configuration bit of line 4 + 4 + 1 + + + RP5 + Rising polarity configuration bit of line 5 + 5 + 1 + + + RP6 + Rising polarity configuration bit of linee 6 + 6 + 1 + + + RP7 + Rising polarity configuration bit of line 7 + 7 + 1 + + + RP8 + Rising polarity configuration bit of line 8 + 8 + 1 + + + RP9 + Rising polarity configuration bit of line 9 + 9 + 1 + + + RP10 + Rising polarity configuration bit of line 10 + 10 + 1 + + + RP11 + Rising polarity configuration bit of line 11 + 11 + 1 + + + RP12 + Rising polarity configuration bit of line 12 + 12 + 1 + + + RP13 + Rising polarity configuration bit of line 13 + 13 + 1 + + + RP14 + Rising polarity configuration bit of line 14 + 14 + 1 + + + RP15 + Rising polarity configuration bit of line 15 + 15 + 1 + + + RP16 + Rising polarity configuration bit of line 16 + 16 + 1 + + + RP17 + Rising polarity configuration bit of line 17 + 17 + 1 + + + RP18 + Rising polarity configuration bit of line 18 + 18 + 1 + + + RP19 + Rising polarity configuration bit of line 19 + 19 + 1 + + + RP20 + Rising polarity configuration bit of line 20 + 20 + 1 + + + RP21 + Rising polarity configuration bit of line 21 + 21 + 1 + + + RP22 + Rising polarity configuration bit of line 22 + 22 + 1 + + + + + POLCFG2 + POLCFG2 + Falling polarity configuration register + 0xC + 0x20 + read-write + 0x00000000 + + + FP0 + Falling polarity event configuration bit of line 0 + 0 + 1 + + + FP1 + Falling polarity event configuration bit of line 1 + 1 + 1 + + + FP2 + Falling polarity event configuration bit of line 2 + 2 + 1 + + + FP3 + Falling polarity event configuration bit of line 3 + 3 + 1 + + + FP4 + Falling polarity event configuration bit of line 4 + 4 + 1 + + + FP5 + Falling polarity event configuration bit of line 5 + 5 + 1 + + + FP6 + Falling polarity event configuration bit of line 6 + 6 + 1 + + + FP7 + Falling polarity event configuration bit of line 7 + 7 + 1 + + + FP8 + Falling polarity event configuration bit of line 8 + 8 + 1 + + + FP9 + Falling polarity event configuration bit of line 9 + 9 + 1 + + + FP10 + Falling polarity event configuration bit of line 10 + 10 + 1 + + + FP11 + Falling polarity event configuration bit of line 11 + 11 + 1 + + + FP12 + Falling polarity event configuration bit of line 12 + 12 + 1 + + + FP13 + Falling polarity event configuration bit of line 13 + 13 + 1 + + + FP14 + Falling polarity event configuration bit of line 14 + 14 + 1 + + + FP15 + Falling polarity event configuration bit of line 15 + 15 + 1 + + + FP16 + Falling polarity event configuration bit of line 16 + 16 + 1 + + + FP17 + Falling polarity event configuration bit of line 17 + 17 + 1 + + + FP18 + Falling polarity event configuration bit of line 18 + 18 + 1 + + + FP19 + Falling polarity event configuration bit of line 19 + 19 + 1 + + + FP20 + Falling polarity event configuration bit of line 20 + 20 + 1 + + + FP21 + Falling polarity event configuration bit of line 21 + 21 + 1 + + + FP22 + Falling polarity event configuration bit of line 22 + 22 + 1 + + + + + SWTRG + SWTRG + Software triggle register + 0x10 + 0x20 + read-write + 0x00000000 + + + SWT0 + Software triggle on line 0 + 0 + 1 + + + SWT1 + Software triggle on line 1 + 1 + 1 + + + SWT2 + Software triggle on line 2 + 2 + 1 + + + SWT3 + Software triggle on line 3 + 3 + 1 + + + SWT4 + Software triggle on line 4 + 4 + 1 + + + SWT5 + Software triggle on line 5 + 5 + 1 + + + SWT6 + Software triggle on line 6 + 6 + 1 + + + SWT7 + Software triggle on line 7 + 7 + 1 + + + SWT8 + Software triggle on line 8 + 8 + 1 + + + SWT9 + Software triggle on line 9 + 9 + 1 + + + SWT10 + Software triggle on line 10 + 10 + 1 + + + SWT11 + Software triggle on line 11 + 11 + 1 + + + SWT12 + Software triggle on line 12 + 12 + 1 + + + SWT13 + Software triggle on line 13 + 13 + 1 + + + SWT14 + Software triggle on line 14 + 14 + 1 + + + SWT15 + Software triggle on line 15 + 15 + 1 + + + SWT16 + Software triggle on line 16 + 16 + 1 + + + SWT17 + Software triggle on line 17 + 17 + 1 + + + SWT18 + Software triggle on line 18 + 18 + 1 + + + SWT19 + Software triggle on line 19 + 19 + 1 + + + SWT20 + Software triggle on line 20 + 20 + 1 + + + SWT21 + Software triggle on line 21 + 21 + 1 + + + SWT22 + Software triggle on line 22 + 22 + 1 + + + + + INTSTS + INTSTS + Interrupt status register + 0x14 + 0x20 + read-write + 0x00000000 + + + LINE0 + Line 0 state bit + 0 + 1 + + + LINE1 + Line 1 state bit + 1 + 1 + + + LINE2 + Line 2 state bit + 2 + 1 + + + LINE3 + Line 3 state bit + 3 + 1 + + + LINE4 + Line 4 state bit + 4 + 1 + + + LINE5 + Line 5 state bit + 5 + 1 + + + LINE6 + Line 6 state bit + 6 + 1 + + + LINE7 + Line 7 state bit + 7 + 1 + + + LINE8 + Line 8 state bit + 8 + 1 + + + LINE9 + Line 9 state bit + 9 + 1 + + + LINE10 + Line 10 state bit + 10 + 1 + + + LINE11 + Line 11 state bit + 11 + 1 + + + LINE12 + Line 12 state bit + 12 + 1 + + + LINE13 + Line 13 state bit + 13 + 1 + + + LINE14 + Line 14 state bit + 14 + 1 + + + LINE15 + Line 15 state bit + 15 + 1 + + + LINE16 + Line 16 state bit + 16 + 1 + + + LINE17 + Line 17 state bit + 17 + 1 + + + LINE18 + Line 18 state bit + 18 + 1 + + + LINE19 + Line 19 state bit + 19 + 1 + + + LINE20 + Line 20 state bit + 20 + 1 + + + LINE21 + Line 21 state bit + 21 + 1 + + + LINE22 + Line 22 state bit + 22 + 1 + + + + + + + EDMA + EDMA controller + EDMA + 0x40026000 + + 0x0 + 0x400 + registers + + + EDMA_Stream1 + EDMA Stream1 global interrupt + 11 + + + EDMA_Stream2 + EDMA Stream2 global interrupt + 12 + + + EDMA_Stream3 + EDMA Stream3 global interrupt + 13 + + + EDMA_Stream4 + EDMA Stream4 global interrupt + 14 + + + EDMA_Stream5 + EDMA Stream5 global interrupt + 15 + + + EDMA_Stream6 + EDMA Stream6 global interrupt + 16 + + + EDMA_Stream7 + EDMA Stream7 global interrupt + 17 + + + EDMA_Stream8 + EDMA Stream8 global interrupt + 47 + + + + STS1 + STS1 + Interrupt status register1 + 0x0 + 0x20 + read-only + 0x00000000 + + + FDTF4 + Stream 4 Full data transfer interrupt flag + + 27 + 1 + + + HDTF4 + Stream 4 half data transfer interrupt flag + + 26 + 1 + + + DTERRF4 + Stream 4 transfer error interrupt flag + + 25 + 1 + + + DMERRF4 + Stream 4 direct mode error interrupt flag + + 24 + 1 + + + FERRF4 + Stream 4 FIFO error interrupt flag + + 22 + 1 + + + FDTF3 + Stream 3 Full data transfer interrupt flag + + 21 + 1 + + + HDTF3 + Stream 3 half data transfer interrupt flag + + 20 + 1 + + + DTERRF3 + Stream 3 transfer error interrupt flag + + 19 + 1 + + + DMERRF3 + Stream 3 direct mode error interrupt flag + + 18 + 1 + + + FERRF3 + Stream 3 FIFO error interrupt flag + + 16 + 1 + + + FDTF2 + Stream 2 Full data transfer interrupt flag + + 11 + 1 + + + HDTF2 + Stream 2 half data transfer interrupt flag + + 10 + 1 + + + DTERRF2 + Stream 2 transfer error interrupt flag + + 9 + 1 + + + DMERRF2 + Stream 2 direct mode error interrupt flag + + 8 + 1 + + + FERRF2 + Stream 2 FIFO error interrupt flag + + 6 + 1 + + + FDTF1 + Stream 1 Full data transfer interrupt flag + + 5 + 1 + + + HDTF1 + Stream 1 half data transfer interrupt flag + + 4 + 1 + + + DTERRF1 + Stream 1 transfer error interrupt flag + + 3 + 1 + + + DMERRF1 + Stream 1 direct mode error interrupt flag + + 2 + 1 + + + FERRF1 + Stream 1 FIFO error interrupt flag + + 0 + 1 + + + + + STS2 + STS2 + Interrupt status register2 + 0x4 + 0x20 + read-only + 0x00000000 + + + FDTF8 + Stream 8 full data transfer interrupt flag + + 27 + 1 + + + HDTF8 + Stream 8 half data transfer interrupt flag + + 26 + 1 + + + DTERRF8 + Stream 8 transfer error interrupt flag + + 25 + 1 + + + DMERRF8 + Stream 8 direct mode error interrupt flag + + 24 + 1 + + + FERRF8 + Stream 8 FIFO error interrupt flag + + 22 + 1 + + + FDTF7 + Stream 7 full data transfer interrupt flag + + 21 + 1 + + + HDTF7 + Stream 7 half data transfer interrupt flag + + 20 + 1 + + + DTERRF7 + Stream 7 transfer error interrupt flag + + 19 + 1 + + + DMERRF7 + Stream 7 direct mode error interrupt flag + + 18 + 1 + + + FERRF7 + Stream 7 FIFO error interrupt flag + + 16 + 1 + + + FDTF6 + Stream 6 full data transfer interrupt flag + + 11 + 1 + + + HDTF6 + Stream 6 half data transfer interrupt flag + + 10 + 1 + + + DTERRF6 + Stream 6 transfer error interrupt flag + + 9 + 1 + + + DMERRF6 + Stream 6 direct mode error interrupt flag + + 8 + 1 + + + FERRF6 + Stream 6 FIFO error interrupt flag + + 6 + 1 + + + FDTF5 + Stream 5 full data transfer interrupt flag + + 5 + 1 + + + HDTF5 + Stream 5 half data transfer interrupt flag + + 4 + 1 + + + DTERRF5 + Stream 5 transfer error interrupt flag + + 3 + 1 + + + DMERRF5 + Stream 5 direct mode error interrupt flag + + 2 + 1 + + + FERRF5 + Stream 5 FIFO error interrupt flag + + 0 + 1 + + + + + CLR1 + CLR1 + Interrupt flag clear register1 + + 0x8 + 0x20 + read-write + 0x00000000 + + + FDTFC4 + Stream 4 clear full data transfer complete interrupt flag + + 27 + 1 + + + HDTFC4 + Stream 4 clear half data transfer interrupt flag + + 26 + 1 + + + DTERRFC4 + Stream 4 clear transfer error interrupt flag + + 25 + 1 + + + DMERRFC4 + Stream 4 clear direct mode error interrupt flag + + 24 + 1 + + + FERRFC4 + Stream 4 clear FIFO error interrupt flag + + 22 + 1 + + + FDTFC3 + Stream 3 clear full data transfer complete interrupt flag + + 21 + 1 + + + HDTFC3 + Stream 3 clear half data transfer interrupt flag + + 20 + 1 + + + DTERRFC3 + Stream 3 clear transfer error interrupt flag + + 19 + 1 + + + DMERRFC3 + Stream 3 clear direct mode error interrupt flag + + 18 + 1 + + + FERRFC3 + Stream 3 clear FIFO error interrupt flag + + 16 + 1 + + + FDTFC2 + Stream 2 clear full data transfer complete interrupt flag + + 11 + 1 + + + HDTFC2 + Stream 2 clear half data transfer interrupt flag + + 10 + 1 + + + DTERRFC2 + Stream 2 clear transfer error interrupt flag + + 9 + 1 + + + DMERRFC2 + Stream 2 clear direct mode error interrupt flag + + 8 + 1 + + + FERRFC2 + Stream 2 clear FIFO error interrupt flag + + 6 + 1 + + + FDTFC1 + Stream 1 clear full data transfer complete interrupt flag + + 5 + 1 + + + HDTFC1 + Stream 1 clear half data transfer interrupt flag + + 4 + 1 + + + DTERRFC1 + Stream 1 clear transfer error interrupt flag + + 3 + 1 + + + DMERRFC1 + Stream 1 clear direct mode error interrupt flag + + 2 + 1 + + + FERRFC1 + Stream 1 clear FIFO error interrupt flag + + 0 + 1 + + + + + CLR2 + CLR2 + Interrupt flag clear register2 + + 0xC + 0x20 + read-write + 0x00000000 + + + FDTFC8 + Stream 8 clear full data transfer complete interrupt flag + + 27 + 1 + + + HDTFC8 + Stream 8 clear half data transfer interrupt flag + + 26 + 1 + + + DTERRFC8 + Stream 8 clear transfer error interrupt flag + + 25 + 1 + + + DMERRFC8 + Stream 8 clear direct mode error interrupt flag + + 24 + 1 + + + FERRFC8 + Stream 8 clear FIFO error interrupt flag + + 22 + 1 + + + FDTFC7 + Stream 7 clear full data transfer complete interrupt flag + + 21 + 1 + + + HDTFC7 + Stream 7 clear half data transfer interrupt flag + + 20 + 1 + + + DTERRFC7 + Stream 7 clear transfer error interrupt flag + + 19 + 1 + + + DMERRFC7 + Stream 7 clear direct mode error interrupt flag + + 18 + 1 + + + FERRFC7 + Stream 7 clear FIFO error interrupt flag + + 16 + 1 + + + FDTFC6 + Stream 6 clear full data transfer complete interrupt flag + + 11 + 1 + + + HDTFC6 + Stream 6 clear half data transfer interrupt flag + + 10 + 1 + + + DTERRFC6 + Stream 6 clear transfer error interrupt flag + + 9 + 1 + + + DMERRFC6 + Stream 6 clear direct mode error interrupt flag + + 8 + 1 + + + FERRFC6 + Stream 6 clear FIFO error interrupt flag + + 6 + 1 + + + FDTFC5 + Stream 5 clear full data transfer complete interrupt flag + + 5 + 1 + + + HDTFC5 + Stream 5 clear half data transfer interrupt flag + + 4 + 1 + + + DTERRFC5 + Stream 5 clear transfer error interrupt flag + + 3 + 1 + + + DMERRFC5 + Stream 5 clear direct mode error interrupt flag + + 2 + 1 + + + FERRFC5 + Stream 5 clear FIFO error interrupt flag + + 0 + 1 + + + + + S1CTRL + S1CTRL + stream 1 control + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1DTCNT + S1DTCNT + stream 1 number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S1PADDR + S1PADDR + stream 1 peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S1M0ADDR + S1M0ADDR + stream 1 memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S1M1ADDR + S1M1ADDR + stream 1 memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCTRL + S1FCTRL + stream 1 FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CTRL + S2CTRL + stream 2 control + register + 0x28 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2DTCNT + S2DTCNT + stream 2 number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S2PADDR + S2PADDR + stream 2 peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S2M0ADDR + S2M0ADDR + stream 2 memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S2M1ADDR + S2M1ADDR + stream 2 memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCTRL + S2FCTRL + stream 2 FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CTRL + S3CTRL + stream 3 control + register + 0x40 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3DTCNT + S3DTCNT + stream 3 number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S3PADDR + S3PADDR + stream 3 peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S3M0ADDR + S3M0ADDR + stream 3 memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S3M1ADDR + S3M1ADDR + stream 3 memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCTRL + S3FCTRL + stream 3 FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CTRL + S4CTRL + stream 4 control + register + 0x58 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4DTCNT + S4DTCNT + stream 4 number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S4PADDR + S4PADDR + stream 4 peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S4M0ADDR + S4M0ADDR + stream 4 memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S4M1ADDR + S4M1ADDR + stream 4 memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCTRL + S4FCTRL + stream 4 FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CTRL + S5CTRL + stream 5 control + register + 0x70 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5DTCNT + S5DTCNT + stream 5 number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S5PADDR + S5PADDR + stream 5 peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S5M0ADDR + S5M0ADDR + stream 5 memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S5M1ADDR + S5M1ADDR + stream 5 memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCTRL + S5FCTRL + stream 5 FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CTRL + S6CTRL + stream 6 control + register + 0x88 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6DTCNT + S6DTCNT + stream 6 number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S6PADDR + S6PADDR + stream 6 peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S6M0ADDR + S6M0ADDR + stream 6 memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S6M1ADDR + S6M1ADDR + stream 6 memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCTRL + S6FCTRL + stream 6 FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CTRL + S7CTRL + stream 7 control + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7DTCNT + S7DTCNT + stream 7 number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S7PADDR + S7PADDR + stream 7 peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S7M0ADDR + S7M0ADDR + stream 7 memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S7M1ADDR + S7M1ADDR + stream 7 memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCTRL + S7FCTRL + stream 7 FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S8CTRL + S8CTRL + stream 8 control + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S8DTCNT + S8DTCNT + stream 8 number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S8PADDR + S8PADDR + stream 8 peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S8M0ADDR + S8M0ADDR + stream 8 memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S8M1ADDR + S8M1ADDR + stream 8 memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S8FCTRL + S8FCTRL + stream 8 FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + LLCTRL + LLCTRL + DMA Link List Control Register + 0xD0 + 0x20 + 0x00000000 + + + S1LLEN + Stream 1 link list enable + 0 + 1 + read-write + + + S2LLEN + Stream 2 link list enable + 1 + 1 + read-write + + + S3LLEN + Stream 3 link list enable + 2 + 1 + read-write + + + S4LLEN + Stream 4 link list enable + 3 + 1 + read-write + + + S5LLEN + Stream 5 link list enable + 4 + 1 + read-write + + + S6LLEN + Stream 6 link list enable + 5 + 1 + read-write + + + S7LLEN + Stream 7 link list enable + 6 + 1 + read-write + + + S8LLEN + Stream 8 link list enable + 7 + 1 + read-write + + + + + S1LLP + S1LLP + Stream 1 Link List Pointer + 0xD4 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S2LLP + S2LLP + Stream 2 Link List Pointer + 0xD8 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S3LLP + S3LLP + Stream 3 Link List Pointer + 0xDC + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S4LLP + S4LLP + Stream 4 Link List Pointer + 0xE0 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S5LLP + S5LLP + Stream 5 Link List Pointer + 0xE4 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S6LLP + S6LLP + Stream 6 Link List Pointer + 0xE8 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S7LLP + S7LLP + Stream 7 Link List Pointer + 0xEC + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S8LLP + S8LLP + Stream 8 Link List Pointer + 0xF0 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S2DCTRL + S2DCTRL + EDMA 2D Transfer Control Register + 0xF4 + 0x20 + 0x00000000 + + + S1_2DEN + Stream 1 2D transfer enable + 0 + 1 + read-write + + + S2_2DEN + Stream 2 2D transfer enable + 1 + 1 + read-write + + + S3_2DEN + Stream 3 2D transfer enable + 2 + 1 + read-write + + + S4_2DEN + Stream 4 2D transfer enable + 3 + 1 + read-write + + + S5_2DEN + Stream 5 2D transfer enable + 4 + 1 + read-write + + + S6_2DEN + Stream 6 2D transfer enable + 5 + 1 + read-write + + + S7_2DEN + Stream 7 2D transfer enable + 6 + 1 + read-write + + + S8_2DEN + Stream 8 2D transfer enable + 7 + 1 + read-write + + + + + S1_2DCNT + S1_2DCNT + Stream 1 2D Transfer Count + 0xF8 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S1_STRIDE + S1_STRIDE + Stream 1 2D Transfer Stride + 0xFC + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S2_2DCNT + S2_2DCNT + Stream 2 2D Transfer Count + 0x100 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S2_STRIDE + S2_STRIDE + Stream 2 2D Transfer Stride + 0x104 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S3_2DCNT + S3_2DCNT + Stream 3 2D Transfer Count + 0x108 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S3_STRIDE + S3_STRIDE + Stream 3 2D Transfer Stride + 0x10C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S4_2DCNT + S4_2DCNT + Stream 4 2D Transfer Count + 0x110 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S4_STRIDE + S4_STRIDE + Stream 4 2D Transfer Stride + 0x114 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S5_2DCNT + S5_2DCNT + Stream 5 2D Transfer Count + 0x118 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S5_STRIDE + S5_STRIDE + Stream 5 2D Transfer Stride + 0x11C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S6_2DCNT + S6_2DCNT + Stream 6 2D Transfer Count + 0x120 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S6_STRIDE + S6_STRIDE + Stream 6 2D Transfer Stride + 0x124 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S7_2DCNT + S7_2DCNT + Stream 7 2D Transfer Count + 0x128 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S7_STRIDE + S7_STRIDE + Stream 7 2D Transfer Stride + 0x12C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S8_2DCNT + S8_2DCNT + Stream 8 2D Transfer Count + 0x130 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S8_STRIDE + S8_STRIDE + Stream 8 2D Transfer Stride + 0x134 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + SYNCEN + SYNCEN + Sync Enable + 0x138 + 0x20 + 0x00000000 + + + S1SYNC + Stream 1 sync enable + 0 + 1 + read-write + + + S2SYNC + Stream 2 sync enable + 1 + 1 + read-write + + + S3SYNC + Stream 3 sync enable + 2 + 1 + read-write + + + S4SYNC + Stream 4 sync enable + 3 + 1 + read-write + + + S5SYNC + Stream 5 sync enable + 4 + 1 + read-write + + + S6SYNC + Stream 6 sync enable + 5 + 1 + read-write + + + S7SYNC + Stream 7 sync enable + 6 + 1 + read-write + + + S8SYNC + Stream 8 sync enable + 7 + 1 + read-write + + + + + MUXSEL + MUXSEL + EDMA MUX Table Selection + 0x13C + 0x20 + 0x00000000 + + + TBL_SEL + Multiplexer Table Select + 0 + 1 + read-write + + + + + MUXS1CTRL + MUXS1CTRL + Stream 1 Configuration Register + 0x140 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS2CTRL + MUXS2CTRL + Stream 2 Configuration Register + 0x144 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS3CTRL + MUXS3CTRL + Stream 3 Configuration Register + 0x148 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS4CTRL + MUXS4CTRL + Stream 4 Configuration Register + 0x14C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS5CTRL + MUXS5CTRL + Stream x Configuration Register + 0x150 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS6CTRL + MUXS6CTRL + Stream 6 Configuration Register + 0x154 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS7CTRL + MUXS7CTRL + Stream 7 Configuration Register + 0x158 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS8CTRL + MUXS8CTRL + Stream 8 Configuration Register + 0x15C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXG1CTRL + MUXG1CTRL + Generator 1 Configuration Register + 0x160 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG2CTRL + MUXG2CTRL + Generator 2 Configuration Register + 0x164 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG3CTRL + MUXG3CTRL + Generator 3 Configuration Register + 0x168 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG4CTRL + MUXG4CTRL + Generator 4 Configuration Register + 0x16C + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXSYNCSTS + MUXSYNCSTS + Channel Interrupt Status Register + 0x170 + 0x20 + 0x00000000 + + + SYNCOVF1 + Synchronizaton overrun interrupt flag + 0 + 1 + read-only + + + SYNCOVF2 + Synchronizaton overrun interrupt flag + 1 + 1 + read-only + + + SYNCOVF3 + Synchronizaton overrun interrupt flag + 2 + 1 + read-only + + + SYNCOVF4 + Synchronizaton overrun interrupt flag + 3 + 1 + read-only + + + SYNCOVF5 + Synchronizaton overrun interrupt flag + 4 + 1 + read-only + + + SYNCOVF6 + Synchronizaton overrun interrupt flag + 5 + 1 + read-only + + + SYNCOVF7 + Synchronizaton overrun interrupt flag + 6 + 1 + read-only + + + SYNCOVF8 + Synchronizaton overrun interrupt flag + 7 + 1 + read-only + + + + + MUXSYNCCLR + MUXSYNCCLR + Channel Interrupt Clear Flag Register + 0x174 + 0x20 + 0x00000000 + + + SYNCOVFC1 + Clear synchronizaton overrun interrupt flag + 0 + 1 + read-write + + + SYNCOVFC2 + Clear synchronizaton overrun interrupt flag + 1 + 1 + read-write + + + SYNCOVFC3 + Clear synchronizaton overrun interrupt flag + 2 + 1 + read-write + + + SYNCOVFC4 + Clear synchronizaton overrun interrupt flag + 3 + 1 + read-write + + + SYNCOVFC5 + Clear synchronizaton overrun interrupt flag + 4 + 1 + read-write + + + SYNCOVFC6 + Clear synchronizaton overrun interrupt flag + 5 + 1 + read-write + + + SYNCOVFC7 + Clear synchronizaton overrun interrupt flag + 6 + 1 + read-write + + + SYNCOVFC8 + Clear synchronizaton overrun interrupt flag + 7 + 1 + read-write + + + + + MUXGSTS + MUXGSTS + Generator Interrupt Status Register + 0x178 + 0x20 + 0x00000000 + + + TRGOVF1 + Trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVF2 + Trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVF3 + Trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVF4 + Trigger overrun interrupt flag + 3 + 1 + read-write + + + + + MUXGCLR + MUXGCLR + Generator Interrupt Clear Flag Register + 0x17C + 0x20 + 0x00000000 + + + TRGOVFC1 + Clear trigger overrun interrupt flag + 0 + 1 + read-write + + + + TRGOVFC2 + Clear trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVFC3 + Clear trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVFC4 + Clear trigger overrun interrupt flag + 3 + 1 + read-write + + + + + + + DMA1 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x200 + registers + + + DMA1_Channel1 + DMA1 Channel1 global interrupt + 56 + + + DMA1_Channel2 + DMA1 Channel2 global interrupt + 57 + + + DMA1_Channel3 + DMA1 Channel3 global interrupt + 58 + + + DMA1_Channel4 + DMA1 Channel4 global interrupt + 59 + + + DMA1_Channel5 + DMA1 Channel5 global interrupt + 60 + + + DMA1_Channel6 + DMA1 Channel6 global interrupt + 68 + + + DMA1_Channel7 + DMA1 Channel7 global interrupt + 69 + + + + STS + STS + DMA interrupt status register + (DMA_STS) + 0x0 + 0x20 + read-only + 0x00000000 + + + GF1 + Channel 1 Global event flag + 0 + 1 + + + FDTF1 + Channel 1 full data transfer event flag + 1 + 1 + + + HDTF1 + Channel 1 half data transfer event flag + 2 + 1 + + + DTERRF1 + Channel 1 data transfer error event flag + 3 + 1 + + + GF2 + Channel 2 Global event flag + 4 + 1 + + + FDTF2 + Channel 2 full data transfer event flag + 5 + 1 + + + HDTF2 + Channel 2 half data transfer event flag + 6 + 1 + + + DTERRF2 + Channel 2 data transfer error event flag + 7 + 1 + + + GF3 + Channel 3 Global event flag + 8 + 1 + + + FDTF3 + Channel 3 full data transfer event flag + 9 + 1 + + + HDTF3 + Channel 3 half data transfer event flag + 10 + 1 + + + DTERRF3 + Channel 3 data transfer error event flag + 11 + 1 + + + GF4 + Channel 4 Global event flag + 12 + 1 + + + FDTF4 + Channel 4 full data transfer event flag + 13 + 1 + + + HDTF4 + Channel 4 half data transfer event flag + 14 + 1 + + + DTERRF4 + Channel 4 data transfer error event flag + 15 + 1 + + + GF5 + Channel 5 Global event flag + 16 + 1 + + + FDTF5 + Channel 5 full data transfer event flag + 17 + 1 + + + HDTF5 + Channel 5 half data transfer event flag + 18 + 1 + + + DTERRF5 + Channel 5 data transfer error event flag + 19 + 1 + + + GF6 + Channel 6 Global event flag + 20 + 1 + + + FDTF6 + Channel 6 full data transfer event flag + 21 + 1 + + + HDTF6 + Channel 6 half data transfer event flag + 22 + 1 + + + DTERRF6 + Channel 6 data transfer error event flag + 23 + 1 + + + GF7 + Channel 7 Global event flag + 24 + 1 + + + FDTF7 + Channel 7 full data transfer event flag + 25 + 1 + + + HDTF7 + Channel 7 half data transfer event flag + 26 + 1 + + + DTERRF7 + Channel 7 data transfer error event flag + 27 + 1 + + + + + CLR + CLR + DMA interrupt flag clear register + (DMA_CLR) + 0x4 + 0x20 + read-write + 0x00000000 + + + GFC1 + Channel 1 Global flag clear + 0 + 1 + + + GFC2 + Channel 2 Global flag clear + 4 + 1 + + + GFC3 + Channel 3 Global flag clear + 8 + 1 + + + GFC4 + Channel 4 Global flag clear + 12 + 1 + + + GFC5 + Channel 5 Global flag clear + 16 + 1 + + + GFC6 + Channel 6 Global flag clear + 20 + 1 + + + GFC7 + Channel 7 Global flag clear + 24 + 1 + + + FDTFC1 + Channel 1 full data transfer flag clear + 1 + 1 + + + FDTFC2 + Channel 2 full data transfer flag clear + 5 + 1 + + + FDTFC3 + Channel 3 full data transfer flag clear + 9 + 1 + + + FDTFC4 + Channel 4 full data transfer flag clear + 13 + 1 + + + FDTFC5 + Channel 5 full data transfer flag clear + 17 + 1 + + + FDTFC6 + Channel 6 full data transfer flag clear + 21 + 1 + + + FDTFC7 + Channel 7 full data transfer flag clear + 25 + 1 + + + HDTFC1 + Channel 1 half data transfer flag clear + 2 + 1 + + + HDTFC2 + Channel 2 half data transfer flag clear + 6 + 1 + + + HDTFC3 + Channel 3 half data transfer flag clear + 10 + 1 + + + HDTFC4 + Channel 4 half data transfer flag clear + 14 + 1 + + + HDTFC5 + Channel 5 half data transfer flag clear + 18 + 1 + + + HDTFC6 + Channel 6 half data transfer flag clear + 22 + 1 + + + HDTFC7 + Channel 7 half data transfer flag clear + 26 + 1 + + + DTERRFC1 + Channel 1 data transfer error flag clear + 3 + 1 + + + DTERRFC2 + Channel 2 data transfer error flag clear + 7 + 1 + + + DTERRFC3 + Channel 3 data transfer error flag clear + 11 + 1 + + + DTERRFC4 + Channel 4 data transfer error flag clear + 15 + 1 + + + DTERRFC5 + Channel 5 data transfer error flag clear + 19 + 1 + + + DTERRFC6 + Channel 6 data transfer error flag clear + 23 + 1 + + + DTERRFC7 + Channel 7 data transfer error flag clear + 27 + 1 + + + + + C1CTRL + C1CTRL + DMA channel configuration register(DMA_C1CTRL) + 0x8 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C1DTCNT + C1DTCNT + DMA channel 1 number of data to transfer register + 0xC + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C1PADDR + C1PADDR + DMA channel 1 peripheral base address register + 0x10 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C1MADDR + C1MADDR + DMA channel 1 memory base address register + 0x14 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C2CTRL + C2CTRL + DMA channel configuration register (DMA_C2CTRL) + 0x1C + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C2DTCNT + C2DTCNT + DMA channel 2 number of data to transferregister + 0x20 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C2PADDR + C2PADDR + DMA channel 2 peripheral base address register + 0x24 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C2MADDR + C2MADDR + DMA channel 2 memory base address register + 0x28 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C3CTRL + C3CTRL + DMA channel configuration register (DMA_C3CTRL) + 0x30 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C3DTCNT + C3DTCNT + DMA channel 3 number of data to transfer register + 0x34 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C3PADDR + C3PADDR + DMA channel 3 peripheral base address register + 0x38 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C3MADDR + C3MADDR + DMA channel 3 memory base address register + 0x3C + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C4CTRL + C4CTRL + DMA channel configuration register (DMA_C4CTRL) + 0x44 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C4DTCNT + C4DTCNT + DMA channel 4 number of data to transfer register + 0x48 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C4PADDR + C4PADDR + DMA channel 4 peripheral base address register + 0x4C + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C4MADDR + C4MADDR + DMA channel 4 memory base address register + 0x50 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C5CTRL + C5CTRL + DMA channel configuration register (DMA_C5CTRL) + 0x58 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C5DTCNT + C5DTCNT + DMA channel 5 number of data to transfer register + 0x5C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C5PADDR + C5PADDR + DMA channel 5 peripheral base address register + 0x60 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C5MADDR + C5MADDR + DMA channel 5 memory base address register + 0x64 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C6CTRL + C6CTRL + DMA channel configuration register(DMA_C6CTRL) + 0x6C + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C6DTCNT + C6DTCNT + DMA channel 6 number of data to transfer register + 0x70 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C6PADDR + C6PADDR + DMA channel 6 peripheral address base register + 0x74 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C6MADDR + C6MADDR + DMA channel 6 memory address base register + 0x78 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C7CTRL + C7CTRL + DMA channel configuration register(DMA_C7CTRL) + 0x80 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C7DTCNT + C7DTCNT + DMA channel 7 number of data to transfer register + 0x84 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C7PADDR + C7PADDR + DMA channel 7 peripheral base address register + 0x88 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C7MADDR + C7MADDR + DMA channel 7 memory base address register + 0x8C + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + DMA_MUXSEL + DMA_MUXSEL + DMAMUX Table Selection + 0x100 + 0x20 + 0x00000000 + + + TBL_SEL + Multiplexer Table Select + 0 + 1 + read-write + + + + + MUXC1CTRL + MUXC1CTRL + Channel 1 Configuration Register + 0x104 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC2CTRL + MUXC2CTRL + Channel 2 Configuration Register + 0x108 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC3CTRL + MUXC3CTRL + Channel 3 Configuration Register + 0x10C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC4CTRL + MUXC4CTRL + Channel 4 Configuration Register + 0x110 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC5CTRL + MUXC5CTRL + Channel 5 Configuration Register + 0x114 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC6CTRL + MUXC6CTRL + Channel 6 Configuration Register + 0x118 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC7CTRL + MUXC7CTRL + Channel 7 Configuration Register + 0x11C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXG1CTRL + MUXG1CTRL + Generator 1 Configuration Register + 0x120 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG2CTRL + MUXG2CTRL + Generator 2 Configuration Register + 0x124 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG3CTRL + MUXG3CTRL + Generator 3 Configuration Register + 0x128 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG4CTRL + MUXG4CTRL + Generator 4 Configuration Register + 0x12C + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXSYNCSTS + MUXSYNCSTS + Channel Interrupt Status Register + 0x130 + 0x20 + 0x00000000 + + + SYNCOVF1 + Synchronizaton overrun interrupt flag + 0 + 1 + read-only + + + SYNCOVF2 + Synchronizaton overrun interrupt flag + 1 + 1 + read-only + + + SYNCOVF3 + Synchronizaton overrun interrupt flag + 2 + 1 + read-only + + + SYNCOVF4 + Synchronizaton overrun interrupt flag + 3 + 1 + read-only + + + SYNCOVF5 + Synchronizaton overrun interrupt flag + 4 + 1 + read-only + + + SYNCOVF6 + Synchronizaton overrun interrupt flag + 5 + 1 + read-only + + + SYNCOVF7 + Synchronizaton overrun interrupt flag + 6 + 1 + read-only + + + + + MUXSYNCCLR + MUXSYNCCLR + Channel Interrupt Clear Flag Register + 0x134 + 0x20 + 0x00000000 + + + SYNCOVFC1 + Clear synchronizaton overrun interrupt flag + 0 + 1 + read-write + + + SYNCOVFC2 + Clear synchronizaton overrun interrupt flag + 1 + 1 + read-write + + + SYNCOVFC3 + Clear synchronizaton overrun interrupt flag + 2 + 1 + read-write + + + SYNCOVFC4 + Clear synchronizaton overrun interrupt flag + 3 + 1 + read-write + + + SYNCOVFC5 + Clear synchronizaton overrun interrupt flag + 4 + 1 + read-write + + + SYNCOVFC6 + Clear synchronizaton overrun interrupt flag + 5 + 1 + read-write + + + SYNCOVFC7 + Clear synchronizaton overrun interrupt flag + 6 + 1 + read-write + + + + + MUXGSTS + MUXGSTS + Generator Interrupt Status Register + 0x138 + 0x20 + 0x00000000 + + + TRGOVF1 + Trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVF2 + Trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVF3 + Trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVF4 + Trigger overrun interrupt flag + 3 + 1 + read-write + + + + + MUXGCLR + MUXGCLR + Generator Interrupt Clear Flag Register + 0x13C + 0x20 + 0x00000000 + + + TRGOVFC1 + Clear trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVFC2 + Clear trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVFC3 + Clear trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVFC4 + Clear trigger overrun interrupt flag + 3 + 1 + read-write + + + + + + + DMA2 + 0x40026600 + + + SDIO1 + Secure digital input/output + interface + SDIO + 0x4002C400 + + 0x0 + 0x400 + registers + + + SDIO1 + SDIO1 global interrupt + 49 + + + + PWRCTRL + PWRCTRL + Bits 1:0 = PWRCTRL: Power supply control + bits + 0x0 + 0x20 + read-write + 0x00000000 + + + PS + Power switch + 0 + 2 + + + + + CLKCTRL + CLKCTRL + SD clock control register + (SDIO_CLKCTRL) + 0x4 + 0x20 + read-write + 0x00000000 + + + CLKDIV + Clock division + 0 + 8 + + + CLKOEN + Clock output enable + 8 + 1 + + + PWRSVEN + Power saving mode enable + 9 + 1 + + + BYPSEN + Clock divider bypass enable + bit + 10 + 1 + + + BUSWS + Bus width selection + 11 + 2 + + + CLKEDS + SDIO_CK edge selection bit + 13 + 1 + + + HFCEN + Hardware flow control enable + 14 + 1 + + + CLKDIV98 + Clock divide factor bit9 and bit8 + 15 + 2 + + + + + ARGU + ARGU + Bits 31:0 = : Command argument + 0x8 + 0x20 + read-write + 0x00000000 + + + ARGU + Command argument + 0 + 32 + + + + + CMDCTRL + CMDCTRL + SDIO command control register + (SDIO_CMDCTRL) + 0xC + 0x20 + read-write + 0x00000000 + + + CMDIDX + CMDIDX + 0 + 6 + + + RSPWT + Wait for response + 6 + 2 + + + INTWT + CCSM wait for interrupt + 8 + 1 + + + PNDWT + CCSM wait for end of transfer + 9 + 1 + + + CCSMEN + Command channel state machine + 10 + 1 + + + IOSUSP + SD I/O suspend command + 11 + 1 + + + + + RSPCMD + RSPCMD + SDIO command register + 0x10 + 0x20 + read-only + 0x00000000 + + + RSPCMD + RSPCMD + 0 + 6 + + + + + RSP1 + RSP1 + Bits 31:0 = CARDSTATUS1 + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTS1 + CARDSTATUS1 + 0 + 32 + + + + + RSP2 + RSP2 + Bits 31:0 = CARDSTATUS2 + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS2 + 0 + 32 + + + + + RSP3 + RSP3 + Bits 31:0 = CARDSTATUS3 + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS3 + 0 + 32 + + + + + RSP4 + RSP4 + Bits 31:0 = CARDSTATUS4 + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS4 + 0 + 32 + + + + + DTTMR + DTTMR + Bits 31:0 = TIMEOUT: Data timeout + period + 0x24 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Data timeout period + 0 + 32 + + + + + DTLEN + DTLEN + Bits 24:0 = DATALENGTH: Data length + value + 0x28 + 0x20 + read-write + 0x00000000 + + + DTLEN + Data length value + 0 + 25 + + + + + DTCTRL + DTCTRL + SDIO data control register + (SDIO_DCTRL) + 0x2C + 0x20 + read-write + 0x00000000 + + + TFREN + DTEN + 0 + 1 + + + TFRDIR + DTDIR + 1 + 1 + + + TFRMODE + DTMODE + 2 + 1 + + + DMAEN + DMAEN + 3 + 1 + + + BLKSIZE + DBLOCKSIZE + 4 + 4 + + + RDWTSTART + PWSTART + 8 + 1 + + + RDWTSTOP + PWSTOP + 9 + 1 + + + RDWTMODE + RWMOD + 10 + 1 + + + IOEN + SD I/O function enable + 11 + 1 + + + + + DTCNT + DTCNT + Bits 24:0 = DATACOUNT: Data count + value + 0x30 + 0x20 + read-only + 0x00000000 + + + CNT + Data count value + 0 + 25 + + + + + STS + STS + SDIO status register + (SDIO_STA) + 0x34 + 0x20 + read-only + 0x00000000 + + + CMDFAIL + Command crc fail + 0 + 1 + + + DTFAIL + Data crc fail + 1 + 1 + + + CMDTIMEOUT + Command timeout + 2 + 1 + + + DTTIMEOUT + Data timeout + 3 + 1 + + + TXERRU + Tx under run error + 4 + 1 + + + RXERRO + Rx over run error + 5 + 1 + + + CMDRSPCMPL + Command response complete + 6 + 1 + + + CMDCMPL + Command sent + 7 + 1 + + + DTCMPL + Data sent + 8 + 1 + + + SBITERR + Start bit error + 9 + 1 + + + DTBLKCMPL + Data block sent + 10 + 1 + + + DOCMD + Command transfer in progress + 11 + 1 + + + DOTX + Data transmit in progress + 12 + 1 + + + DORX + Data receive in progress + 13 + 1 + + + TXBUFH + Tx buffer half empty + 14 + 1 + + + RXBUFH + Rx buffer half empty + 15 + 1 + + + TXBUFF + Tx buffer full + 16 + 1 + + + RXBUFF + Rx buffer full + 17 + 1 + + + TXBUFE + Tx buffer empty + 18 + 1 + + + RXBUFE + Rx buffer empty + 19 + 1 + + + TXBUF + Tx data vaild + 20 + 1 + + + RXBUF + Rx data vaild + 21 + 1 + + + IOIF + SD I/O interrupt + 22 + 1 + + + + + INTCLR + INTCLR + SDIO interrupt clear register + (SDIO_INTCLR) + 0x38 + 0x20 + read-write + 0x00000000 + + + CMDFAIL + Command crc fail flag clear + 0 + 1 + + + DTFAIL + Data crc fail flag clear + 1 + 1 + + + CMDTIMEOUT + Command timeout flag clear + 2 + 1 + + + DTTIMEOUT + Data timeout flag clear + 3 + 1 + + + TXERRU + Tx under run error flag clear + 4 + 1 + + + RXERRU + Rx over run error flag clear + 5 + 1 + + + CMDRSPCMPL + Command response complete flag clear + 6 + 1 + + + CMDCMPL + Command sent flag clear + 7 + 1 + + + DTCMPL + Data sent flag clear + 8 + 1 + + + SBITERR + Start bit error flag clear + 9 + 1 + + + DTBLKCMPL + Data block sent clear + 10 + 1 + + + IOIF + SD I/O interrupt flag clear + 22 + 1 + + + + + INTEN + INTEN + SDIO mask register (SDIO_MASK) + 0x3C + 0x20 + read-write + 0x00000000 + + + CMDFAILIEN + Command crc fail interrupt enable + 0 + 1 + + + DTFAILIEN + Data crc fail interrupt enable + 1 + 1 + + + CMDTIMEOUTIEN + Command timeout interrupt enable + 2 + 1 + + + DTTIMEOUTIEN + Data timeout interrupt enable + 3 + 1 + + + TXERRUIEN + Tx under run interrupt enable + 4 + 1 + + + RXERRUIEN + Rx over run interrupt enable + 5 + 1 + + + CMDRSPCMPLIEN + Command response complete interrupt enable + 6 + 1 + + + CMDCMPLIEN + Command sent complete interrupt enable + 7 + 1 + + + DTCMPLIEN + Data sent complete interrupt enable + 8 + 1 + + + SBITERRIEN + Start bit error interrupt enable + 9 + 1 + + + DTBLKCMPLIEN + Data block sent complete interrupt enable + 10 + 1 + + + DOCMDIEN + Command acting interrupt enable + 11 + 1 + + + DOTXIEN + Data transmit acting interrupt enable + 12 + 1 + + + DORXIEN + Data receive acting interrupt enable + 13 + 1 + + + TXBUFHIEN + Tx buffer half empty interrupt enable + 14 + 1 + + + RXBUFHIEN + Rx buffer half empty interrupt enable + 15 + 1 + + + TXBUFFIEN + Tx buffer full interrupt enable + 16 + 1 + + + RXBUFFIEN + Rx buffer full interrupt enable + 17 + 1 + + + TXBUFEIEN + Tx buffer empty interrupt enable + 18 + 1 + + + RXBUFEIEN + Rx buffer empty interrupt enable + 19 + 1 + + + TXBUFIEN + Tx buffer data vaild interrupt enable + 20 + 1 + + + RXBUFIEN + Rx buffer data vaild interrupt enable + 21 + 1 + + + IOIFIEN + SD I/O interrupt enable + 22 + 1 + + + + + BUFCNT + BUFCNT + Bits 23:0 = BUFCOUNT: Remaining number of + words to be written to or read from the + FIFO + 0x48 + 0x20 + read-only + 0x00000000 + + + CNT + FIF0COUNT + 0 + 24 + + + + + BUF + BUF + bits 31:0 = Buffer Data: Receive and transmit + buffer data + 0x80 + 0x20 + read-write + 0x00000000 + + + DT + Buffer data + 0 + 32 + + + + + + + SDIO2 + 0x50061000 + + SDIO2 + SDIO2 global interrupt + 102 + + + + ERTC + Real-time clock + ERTC + 0x40002800 + + 0x0 + 0x400 + registers + + + + TIME + TIME + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + AMPM + AM/PM notation + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + DATE + DATE + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens + 20 + 4 + + + YU + Year units + 16 + 4 + + + WK + Week + 13 + 3 + + + MT + Month tens + 12 + 1 + + + MU + Month units + 8 + 4 + + + DT + Date tens + 4 + 2 + + + DU + Date units + 0 + 4 + + + + + CTRL + CTRL + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + CALOEN + Calibration output enable + 23 + 1 + + + OUTSEL + Output source selection + 21 + 2 + + + OUTP + Output polarity + 20 + 1 + + + CALOSEL + Calibration output selection + 19 + 1 + + + BPR + Battery power domain data register + 18 + 1 + + + DEC1H + Decrease 1 hour + 17 + 1 + + + ADD1H + Add 1 hour + 16 + 1 + + + TSIEN + Timestamp interrupt enable + 15 + 1 + + + WATIEN + Wakeup timer interrupt enable + 14 + 1 + + + ALBIEN + Alarm B interrupt enable + 13 + 1 + + + ALAIEN + Alarm A interrupt enable + 12 + 1 + + + TSEN + Timestamp enable + 11 + 1 + + + WATEN + Wakeup timer enable + 10 + 1 + + + ALBEN + Alarm B enable + 9 + 1 + + + ALAEN + Alarm A enable + 8 + 1 + + + CCALEN + Coarse calibration enable + 7 + 1 + + + HM + Hour mode + 6 + 1 + + + DREN + Date/time register direct read enable + 5 + 1 + + + RCDEN + Reference clock detection enable + 4 + 1 + + + TSEDG + Timestamp trigger edge + 3 + 1 + + + WATCLK + Wakeup timer clock selection + 0 + 3 + + + + + STS + STS + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALAWF + Alarm A register allows write flag + 0 + 1 + read-only + + + ALBWF + Alarm B register allows write flag + 1 + 1 + read-only + + + WATWF + Wakeup timer register allows write flag + 2 + 1 + read-only + + + TADJF + Time adjustment flag + 3 + 1 + read-write + + + INITF + Calendar initialization flag + 4 + 1 + read-only + + + UPDF + Calendar update flag + 5 + 1 + read-write + + + IMF + Enter initialization mode flag + 6 + 1 + read-only + + + IMEN + Initialization mode enable + 7 + 1 + read-write + + + ALAF + Alarm A flag + 8 + 1 + read-write + + + ALBF + Alarm B flag + 9 + 1 + read-write + + + WATF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Timestamp flag + 11 + 1 + read-write + + + TSOF + Timestamp overflow flag + 12 + 1 + read-write + + + TP1F + Tamper detection 1 flag + 13 + 1 + read-write + + + TP2F + Tamper detection 2 flag + 14 + 1 + read-write + + + CALUPDF + Calibration value update completed flag + 16 + 1 + read-only + + + + + DIV + DIV + Diveder register + 0x10 + 0x20 + read-write + 0x007F00FF + + + DIVA + Diveder A + 16 + 7 + + + DIVB + Diveder B + 0 + 15 + + + + + WAT + WAT + Wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + VAL + Wakeup timer reload value + 0 + 16 + + + + + CCAL + CCAL + Calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + CALDIR + Calibration direction + 7 + 1 + + + CALVAL + Calibration value + 0 + 5 + + + + + ALA + ALA + Alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MASK4 + Date/week mask + 31 + 1 + + + WKSEL + Date/week mode select + 30 + 1 + + + DT + Date tens + 28 + 2 + + + DU + Date units + 24 + 4 + + + MASK3 + Hours mask + 23 + 1 + + + AMPM + AM/PM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MASK2 + Minutes mask + 15 + 1 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + MASK1 + Seconds mask + 7 + 1 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + ALB + ALB + Alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MASK4 + Date/week mask + 31 + 1 + + + WKSEL + Date/week mode select + 30 + 1 + + + DT + Date tens + 28 + 2 + + + DU + Date units + 24 + 4 + + + MASK3 + Hours mask + 23 + 1 + + + AMPM + AM/PM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MASK2 + Minutes mask + 15 + 1 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + MASK1 + Seconds mask + 7 + 1 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + WP + WP + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + CMD + Command register + 0 + 8 + + + + + SBS + SBS + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SBS + Sub second value + 0 + 16 + + + + + TADJ + TADJ + time adjust register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add 1 second + 31 + 1 + + + DECSBS + Decrease sub-second value + 0 + 15 + + + + + TSTM + TSTM + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + AMPM + AMPM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + TSDT + TSDT + timestamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WK + Week + 13 + 3 + + + MT + Month tens + 12 + 1 + + + MU + Month units + 8 + 4 + + + DT + Date tens + 4 + 2 + + + DU + Date units + 0 + 4 + + + + + TSSBS + TSSBS + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SBS + Sub second value + 0 + 16 + + + + + SCAL + SCAL + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + ADD + Add ERTC clock + 15 + 1 + + + CAL8 + 8-second calibration period + 14 + 1 + + + CAL16 + 16 second calibration period + 13 + 1 + + + DEC + Decrease ERTC clock + 0 + 9 + + + + + TAMP + TAMP + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + OUTTYPE + Output type + 18 + 1 + + + TSPIN + Time stamp detection pin selection + 17 + 1 + + + TP1PIN + Tamper detection pin selection + 16 + 1 + + + TPPU + Tamper detection pull-up + 15 + 1 + + + TPPR + Tamper detection pre-charge time + 13 + 2 + + + TPFLT + Tamper detection filter time + 11 + 2 + + + TPFREQ + Tamper detection frequency + 8 + 3 + + + TPTSEN + Tamper detection timestamp enable + 7 + 1 + + + TP2EDG + Tamper detection 2 valid edge + 4 + 1 + + + TP2EN + Tamper detection 2 enable + 3 + 1 + + + TPIEN + Tamper detection interrupt enable + 2 + 1 + + + TP1EDG + Tamper detection 1 valid edge + 1 + 1 + + + TP1EN + Tamper detection 1 enable + 0 + 1 + + + + + ALASBS + ALASBS + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + SBSMSK + Sub-second mask + 24 + 4 + + + SBS + Sub-seconds value + 0 + 15 + + + + + ALBSBS + ALBSBS + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + SBSMSK + Sub-second mask + 24 + 4 + + + SBS + Sub-seconds value + 0 + 15 + + + + + BPR1DT + BPR1DT + Battery powered domain register + 0x50 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR2DT + BPR2DT + Battery powered domain register + 0x54 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR3DT + BPR3DT + Battery powered domain register + 0x58 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR4DT + BPR4DT + Battery powered domain register + 0x5C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR5DT + BPR5DT + Battery powered domain register + 0x60 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR6DT + BPR6DT + Battery powered domain register + 0x64 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR7DT + BPR7DT + Battery powered domain register + 0x68 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR8DT + BPR8DT + Battery powered domain register + 0x6C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR9DT + BPR9DT + Battery powered domain register + 0x70 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR10DT + BPR10DT + Battery powered domain register + 0x74 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR11DT + BPR11DT + Battery powered domain register + 0x78 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR12DT + BPR12DT + Battery powered domain register + 0x7C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR13DT + BPR13DT + Battery powered domain register + 0x80 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR14DT + BPR14DT + Battery powered domain register + 0x84 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR15DT + BPR15DT + Battery powered domain register + 0x88 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR16DT + BPR16DT + Battery powered domain register + 0x8C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR17DT + BPR17DT + Battery powered domain register + 0x90 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR18DT + BPR18DT + Battery powered domain register + 0x94 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR19DT + BPR19DT + Battery powered domain register + 0x98 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR20DT + BPR20DT + Battery powered domain register + 0x9C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + + + WDT + Watchdog + WDT + 0x40003000 + + 0x0 + 0x400 + registers + + + + CMD + CMD + Command register + 0x0 + 0x20 + write-only + 0x00000000 + + + CMD + Command register + 0 + 16 + + + + + DIV + DIV + Division register + 0x4 + 0x20 + read-write + 0x00000000 + + + DIV + Division divider + 0 + 3 + + + + + RLD + RLD + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RLD + Reload value + 0 + 12 + + + + + STS + STS + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + DIVF + Division value update complete flag + 0 + 1 + + + RLDF + Reload value update complete flag + 1 + 1 + + + WINF + Window value update complete flag + 2 + 1 + + + + + WIN + WIN + Window register + 0x10 + 0x20 + read-write + 0x00000FFF + + + WIN + Window value + 0 + 12 + + + + + + + WWDT + Window watchdog + WWDT + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDT + Window Watchdog interrupt + 0 + + + + CTRL + CTRL + Control register + 0x0 + 0x20 + read-write + 0x0000007F + + + CNT + Decrement counter + 0 + 7 + + + WWDTEN + Window watchdog enable + 7 + 1 + + + + + CFG + CFG + Configuration register + 0x4 + 0x20 + read-write + 0x0000007F + + + WIN + Window value + 0 + 7 + + + DIV + Clock division value + 7 + 2 + + + RLDIEN + Reload counter interrupt + 9 + 1 + + + + + STS + STS + Status register + 0x8 + 0x20 + read-write + 0x00000000 + + + RLDF + Reload counter interrupt flag + 0 + 1 + + + + + + + TMR1 + Advanced timer + TIMER + 0x40010000 + + 0x0 + 0x400 + registers + + + TMR1_BRK_TMR9 + TMR1 brake interrupt and TMR9 global + interrupt + 24 + + + TMR1_OVF_TMR10 + TMR1 overflow interrupt and TMR10 global + interrupt + 25 + + + TMR1_TRG_HALL_TMR11 + TMR1 trigger and HALL interrupts and + TMR11 global interrupt + 26 + + + TMR1_CH + TMR1 channel interrupt + 27 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TRGOUT2EN + TRGOUT2 enable + 31 + 1 + + + C4IOS + Channel 4 idle output state + 14 + 1 + + + C3CIOS + Channel 3 complementary idle output state + 13 + 1 + + + C3IOS + Channel 3 idle output state + 12 + 1 + + + C2CIOS + Channel 2 complementary idle output state + 11 + 1 + + + C2IOS + Channel 2 idle output state + 10 + 1 + + + C1CIOS + Channel 1 complementary idle output state + 9 + 1 + + + C1IOS + Channel 1 idle output state + 8 + 1 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + CCFS + Channel control bit flash select + 2 + 1 + + + CBCTRL + Channel buffer control + 0 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + HALLDE + HALL DMA request enable + 13 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + BRKIE + Brake interrupt enable + 7 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + HALLIEN + HALL interrupt enable + 5 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + BRKIF + Brake interrupt flag + 7 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + HALLIF + HALL interrupt flag + 5 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + BRKSWTR + Brake event triggered by software + 7 + 1 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + HALLSWTR + HALL event triggered by software + 5 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3CP + Channel 3 complementary polarity + 11 + 1 + + + C3CEN + Channel 3 complementary enable + 10 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2CP + Channel 2 complementary polarity + 7 + 1 + + + C2CEN + Channel 2 complementary enable + 6 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1CEN + Channel 1 complementary enable + 2 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + RPR + RPR + Repetition of period value + 0x30 + 0x20 + read-write + 0x0000 + + + RPR + Repetition of period value + 0 + 8 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 16 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 16 + + + + + BRK + BRK + Brake register + 0x44 + 0x20 + read-write + 0x0000 + + + OEN + Output enable + 15 + 1 + + + AOEN + Automatic output enable + 14 + 1 + + + BRKV + Brake input validity + 13 + 1 + + + BRKEN + Brake enable + 12 + 1 + + + FCSOEN + Frozen channel status when + holistic output enable + 11 + 1 + + + FCSODIS + Frozen channel status when + holistic output disable + 10 + 1 + + + WPC + Write protected configuration + 8 + 2 + + + DTC + Dead-time configuration + 0 + 8 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + CM3_OUTPUT + CM3_OUTPUT + Channel output mode register + 0x70 + 0x20 + read-write + 0x00000000 + + + C5OSEN + Channel 5 output switch enable + 7 + 1 + + + C5OCTRL + Channel 5 output control + 4 + 3 + + + C5OBEN + Channel 5 output buffer enable + 3 + 1 + + + C5OIEN + Channel 5 output immediately enable + 2 + 1 + + + + + C5DT + C5DT + Channel 5 data register + 0x74 + 0x20 + read-write + 0x00000000 + + + C5DT + Channel 5 data register + 0 + 16 + + + + + + + TMR8 + 0x40010400 + + TMR8_BRK_TMR12 + TMR8 brake interrupt and TMR12 global + interrupt + 43 + + + TMR8_OVF_TMR13 + TMR8 overflow interrupt and TMR13 global + interrupt + 44 + + + TMR8_TRG_HALL_TMR14 + TMR8 trigger and HALL interrupts and + TMR14 global interrupt + 45 + + + TMR8_CH + TMR8 channel interrupt + 46 + + + + TMR20 + 0x40014C00 + + TMR20_BRK + TMR20 brake interrupt + 104 + + + TMR20_OVF + TMR20 overflow interrupt + 105 + + + TMR20_TRG_HALL + TMR20 trigger and HALL interrupts + 106 + + + TMR20_CH + TMR20 channel interrupt + 107 + + + + TMR2 + General purpose timer + TIMER + 0x40000000 + + 0x0 + 0x400 + registers + + + TMR2 + TMR2 global interrupt + 28 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PMEN + Plus Mode Enable + 10 + 1 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 32 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 32 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 32 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 32 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 32 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 32 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + TMR2_RMP + TMR2_RMP + TMR2 channel input remap register + 0x50 + 0x20 + read-write + 0x0000 + + + TMR2_CH1_IRMP + TMR2 channel 1 input remap + 10 + 2 + + + + + + + TMR3 + General purpose timer + TIMER + 0x40000400 + + 0x0 + 0x400 + registers + + + TMR3 + TMR3 global interrupt + 29 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 16 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 16 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + + + TMR4 + 0x40000800 + + TMR4 + TMR4 global interrupt + 30 + + + + TMR5 + General purpose timer + TIMER + 0x40000C00 + + 0x0 + 0x400 + registers + + + TMR5 + TMR5 global interrupt + 50 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PMEN + Plus Mode Enable + 10 + 1 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 32 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 32 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 32 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 32 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 32 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 32 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + TMR5_RMP + TMR5_RMP + TMR5 channel input remap register + 0x50 + 0x20 + read-write + 0x0000 + + + TMR5_CH4_IRMP + TMR5 channel 4 input remap + 6 + 2 + + + + + + + TMR9 + General purpose timer + TIMER + 0x40014000 + + 0x0 + 0x400 + registers + + + TMR1_BRK_TMR9 + TMR1 brake interrupt and TMR9 global + interrupt + 24 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C2CP + Channel 2 complementary polarity + 7 + 1 + + + C2CEN + Channel 2 complementary enable + 6 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1CEN + Channel 1 complementary enable + 2 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + + + TMR12 + 0x40001800 + + TMR8_BRK_TMR12 + TMR8 brake interrupt and TMR12 global + interrupt + 43 + + + + TMR10 + General purpose timer + TIMER + 0x40014400 + + 0x0 + 0x400 + registers + + + TMR1_OVF_TMR10 + TMR1 overflow interrupt and TMR10 global + interrupt + 25 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + + + TMR11 + 0x40014800 + + TMR1_TRG_HALL_TMR11 + TMR1 trigger and HALL interrupts and + TMR11 global interrupt + 26 + + + + TMR13 + 0x40001C00 + + TMR8_OVF_TMR13 + TMR8 overflow interrupt and TMR13 global + interrupt + 44 + + + + TMR14 + 0x40002000 + + TMR8_TRG_HALL_TMR14 + TMR8 trigger and HALL interrupts and + TMR14 global interrupt + 45 + + + + TMR6 + Basic timer + TIMER + 0x40001000 + + 0x0 + 0x400 + registers + + + TMR6 + TMR6 global interrupt + 54 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + PTOS + Primary TMR output selection + 4 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + + + TMR7 + 0x40001400 + + TMR7 + TMR7 global interrupt + 55 + + + + ACC + HSI Auto Clock Calibration + ACC + 0x40017400 + + 0x0 + 0x400 + registers + + + + STS + STS + status register + 0x0 + 0x20 + 0x0000 + + + RSLOST + Reference Signal Lost + read-write + 1 + 1 + + + CALRDY + Internal high-speed clock calibration ready + read-write + 0 + 1 + + + + + CTRL1 + CTRL1 + control register 1 + 0x04 + 0x20 + 0x0100 + + + STEP + STEP + read-write + 8 + 4 + + + CALRDYIEN + CALRDY interrupt enable + read-write + 5 + 1 + + + EIEN + RSLOST error interrupt enable + read-write + 4 + 1 + + + SOFSEL + SOF Select + read-write + 2 + 1 + + + ENTRIM + Enable trim + read-write + 1 + 1 + + + CALON + Calibration on + read-write + 0 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x08 + 0x20 + 0x2080 + + + HICKTWK + Internal high-speed auto clock trimming + read-only + 8 + 6 + + + HICKCAL + Internal high-speed auto clock calibration + read-only + 0 + 8 + + + + + C1 + C1 + compare value 1 + 0x0C + 0x20 + 0x1F2C + + + C1 + Compare 1 + read-write + 0 + 16 + + + + + C2 + C2 + compare value 2 + 0x10 + 0x20 + 0x1F40 + + + C2 + Compare 2 + read-write + 0 + 16 + + + + + C3 + C3 + compare value 3 + 0x14 + 0x20 + 0x1F54 + + + C3 + Compare 3 + read-write + 0 + 16 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EVT + I2C1 event interrupt + 31 + + + I2C1_ERR + I2C1 error interrupt + 32 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + 0x00000000 + + + I2CEN + I2C peripheral enable + 0 + 1 + read-write + + + TDIEN + Transmit data interrupt enable + 1 + 1 + read-write + + + RDIEN + Receive data interrupt enable + 2 + 1 + read-write + + + ADDRIEN + Address match interrupt enable + 3 + 1 + read-write + + + ACKFAILIEN + Acknowledge fail interrupt enable + 4 + 1 + read-write + + + STOPIEN + Stop generation complete interrupt enable + 5 + 1 + read-write + + + TDCIEN + Transfer data complete interrupt enable + 6 + 1 + read-write + + + ERRIEN + Error interrupts enable + 7 + 1 + read-write + + + DFLT + Digital filter value + 8 + 4 + read-write + + + DMATEN + DMA Transmit data request enable + 14 + 1 + read-write + + + DMAREN + DMA receive data request enable + 15 + 1 + read-write + + + SCTRL + Slave receiving data control + 16 + 1 + read-write + + + STRETCH + Clock stretching mode + 17 + 1 + read-write + + + GCAEN + General call address enable + 19 + 1 + read-write + + + HADDREN + SMBus host address enable + 20 + 1 + read-write + + + DEVADDREN + SMBus device default address enable + 21 + 1 + read-write + + + SMBALERT + SMBus alert enable / pin set + 22 + 1 + read-write + + + PECEN + PEC calculation enable + 23 + 1 + read-write + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECTEN + Request PEC transmission enable + 26 + 1 + + + ASTOPEN + Automatically send stop condition enable + 25 + 1 + + + RLDEN + Send data reload mode enable + 24 + 1 + + + CNT + Transmit data counter + 16 + 8 + + + NACKEN + Not acknowledge enable + 15 + 1 + + + GENSTOP + Generate stop condition + 14 + 1 + + + GENSTART + Generate start condition + 13 + 1 + + + READH10 + 10-bit address header read enable + 12 + 1 + + + ADDR10 + Host send 10-bit address mode enable + 11 + 1 + + + DIR + Master data transmission direction + 10 + 1 + + + SADDR + Slave address + 0 + 10 + + + + + OADDR1 + OADDR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + ADDR1 + Interface address + 0 + 10 + + + ADDR1MODE + Own Address mode + 10 + 1 + + + ADDR1EN + Own address 1 enable + 15 + 1 + + + + + OADDR2 + OADDR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + ADDR2 + Own address 2 + 1 + 7 + + + ADDR2MASK + Own address 2-bit mask + 8 + 3 + + + ADDR2EN + Own address 2 enable + 15 + 1 + + + + + CLKCTRL + CLKCTRL + Clock contorl register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low level + 0 + 8 + + + SCLH + SCL high level + 8 + 8 + + + SDAD + SDA output delay + 16 + 4 + + + SCLD + SCL output delay + 20 + 4 + + + DIVH + High 4 bits of clock divider value + 24 + 4 + + + DIVL + Low 4 bits of clock divider value + 28 + 4 + + + + + TIMEOUT + TIMEOUT + Timeout register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTIME + Clock timeout detection time + 0 + 12 + + + TOMOED + Clock timeout detection mode + 12 + 1 + + + TOEN + Detect clock low/high timeout enable + 15 + 1 + + + EXTTIME + Cumulative clock low extend timeout value + 16 + 12 + + + EXTEN + Cumulative clock low extend timeout enable + 31 + 1 + + + + + STS + STS + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDR + Slave address matching value + 17 + 7 + read-only + + + SDIR + Slave data transmit direction + 16 + 1 + read-only + + + BUSYF + Bus busy + 15 + 1 + read-only + + + ALERTF + SMBus alert flag + 13 + 1 + read-only + + + TMOUT + SMBus timeout flag + 12 + 1 + read-only + + + PECERR + PEC receive error flag + 11 + 1 + read-only + + + OUF + Overflow or underflow flag + 10 + 1 + read-only + + + ARLOST + Arbitration lost flag + 9 + 1 + read-only + + + BUSERR + Bus error flag + 8 + 1 + read-only + + + TCRLD + Transmission is complete, waiting to load data + 7 + 1 + read-only + + + TDC + Transmit data complete flag + 6 + 1 + read-only + + + STOPF + Stop condition generation complete flag + 5 + 1 + read-only + + + ACKFAIL + Acknowledge failure flag + 4 + 1 + read-only + + + ADDRF + 0~7 bit address match flag + 3 + 1 + read-only + + + RDBF + Receive data buffer full flag + 2 + 1 + read-only + + + TDIS + Send interrupt status + 1 + 1 + read-write + + + TDBE + Transmit data buffer empty flag + 0 + 1 + read-write + + + + + CLR + CLR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTC + Clear SMBus alert flag + 13 + 1 + + + TMOUTC + Clear SMBus timeout flag + 12 + 1 + + + PECERRC + Clear PEC receive error flag + 11 + 1 + + + OUFC + Clear overload / underload flag + 10 + 1 + + + ARLOSTC + Clear arbitration lost flag + 9 + 1 + + + BUSERRC + Clear bus error flag + 8 + 1 + + + STOPC + Clear stop condition generation complete flag + 5 + 1 + + + ACKFAILC + Clear acknowledge failure flag + 4 + 1 + + + ADDRC + Clear 0~7 bit address match flag + 3 + 1 + + + + + PEC + PEC + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PECVAL + PEC value + 0 + 8 + + + + + RXDT + RXDT + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + DT + Receive data register + 0 + 8 + + + + + TXDT + TXDT + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + DT + Transmit data register + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + I2C2_EVT + I2C2 event interrupt + 33 + + + I2C2_ERR + I2C2 error interrupt + 34 + + + + I2C3 + 0x40005C00 + + I2C3_EVT + I2C3 event interrupt + 72 + + + I2C3_ERR + I2C3 error interrupt + 73 + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CTRL1 + CTRL1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SLBEN + Single line bidirectional half-duplex enable + 15 + 1 + + + SLBTD + Single line bidirectional half-duplex transmission direction + 14 + 1 + + + CCEN + CRC calculation enable + 13 + 1 + + + NTC + Next transmission CRC + 12 + 1 + + + FBN + frame bit num + 11 + 1 + + + ORA + Only receive active + 10 + 1 + + + SWCSEN + Software CS enable + 9 + 1 + + + SWCSIL + Software CS internal level + 8 + 1 + + + LTF + LSB transmit first + 7 + 1 + + + SPIEN + SPI enable + 6 + 1 + + + MDIV2_0 + Master clock frequency division bit2-0 + 3 + 3 + + + MSTEN + Master enable + 2 + 1 + + + CLKPOL + Clock polarity + 1 + 1 + + + CLKPHA + Clock phase + 0 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MDIV3EN + Master clock frequency3 division enable + 9 + 1 + + + MDIV3 + Master clock frequency division bit3 + 8 + 1 + + + TDBEIE + Transmit data buffer empty interrupt enable + 7 + 1 + + + RDBFIE + Receive data buffer full interrupt enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + TIEN + TI mode enable + 4 + 1 + + + HWCSOE + Hardware CS output enable + 2 + 1 + + + DMATEN + DMA transmit enable + 1 + 1 + + + DMAREN + DMA receive enable + 0 + 1 + + + + + STS + STS + status register + 0x8 + 0x20 + 0x0002 + + + CSPAS + CS pulse abnormal setting fiag + 8 + 1 + read-write + + + BF + Busy flag + 7 + 1 + read-only + + + ROERR + Receiver overflow error + 6 + 1 + read-only + + + MMERR + Master mode error + 5 + 1 + read-only + + + CCERR + CRC calculation error + 4 + 1 + read-write + + + TUERR + Transmitter underload error + 3 + 1 + read-only + + + ACS + Audio channel state + 2 + 1 + read-only + + + TDBE + Transmit data buffer empty + 1 + 1 + read-only + + + RDBF + Receive data buffer full + 0 + 1 + read-only + + + + + DT + DT + data register + 0xC + 0x20 + read-write + 0x0000 + + + DT + Data value + 0 + 16 + + + + + CPOLY + CPOLY + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CPOLY + CRC polynomial + 0 + 16 + + + + + RCRC + RCRC + Receive CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RCRC + Receive CRC + 0 + 16 + + + + + TCRC + TCRC + Transmit CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TCRC + Transmit CRC + 0 + 16 + + + + + I2SCTRL + I2SCTRL + I2S control register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMSEL + I2S mode select + 11 + 1 + + + I2SEN + I2S Enable + 10 + 1 + + + OPERSEL + I2S operation select + 8 + 2 + + + PCMFSSEL + PCM frame synchronization select + 7 + 1 + + + STDSEL + I2S standard select + 4 + 2 + + + I2SCLKPOL + I2S clock polarity + 3 + 1 + + + I2SDBN + I2S data bit num + 1 + 2 + + + I2SCBN + I2S channel bit num + 0 + 1 + + + + + I2SCLK + I2SCLK + I2S clock register + 0x20 + 0x20 + read-write + 00000010 + + + I2SDIV9_8 + I2S division bit9 and bit8 + 10 + 2 + + + I2SMCLKOE + I2S master clock output enable + 9 + 1 + + + I2SODD + Odd result for I2S division + 8 + 1 + + + I2SDIV7_0 + I2S division bit7 to bit0 + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + SPI4 + 0x40013400 + + SPI4 + SPI4 global interrupt + 84 + + + + I2S2_EXT + 0x40017800 + + + I2S3_EXT + 0x40017C00 + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011000 + + 0x0 + 0x400 + registers + + + USART1 + USART1 global interrupt + 37 + + + + STS + STS + Status register + 0x0 + 0x20 + 0x00C0 + + + CTSCF + CTS change flag + 9 + 1 + read-write + + + BFF + Break frame flag + 8 + 1 + read-write + + + TDBE + Transmit data buffer empty + 7 + 1 + read-only + + + TDC + Transmit data complete + 6 + 1 + read-write + + + RDBF + Receive data buffer full + 5 + 1 + read-write + + + IDLEF + IDLE flag + 4 + 1 + read-only + + + ROERR + Receiver overflow error + 3 + 1 + read-only + + + NERR + Noise error + 2 + 1 + read-only + + + FERR + Framing error + 1 + 1 + read-only + + + PERR + Parity error + 0 + 1 + read-only + + + + + DT + DT + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DT + Data value + 0 + 9 + + + + + BAUDR + BAUDR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV + Division + 0 + 16 + + + + + CTRL1 + CTRL1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + DBN1 + high bit for Data bit num + 28 + 1 + + + TSDT + transmit start delay time + 21 + 5 + + + TCDT + transmit complete delay time + 16 + 5 + + + UEN + USART enable + 13 + 1 + + + DBN0 + low bit for Data bit num + 12 + 1 + + + WUM + Wake up mode + 11 + 1 + + + PEN + Parity enable + 10 + 1 + + + PSEL + Parity selection + 9 + 1 + + + PERRIEN + PERR interrupt enable + 8 + 1 + + + TDBEIEN + TDBE interrupt enable + 7 + 1 + + + TDCIEN + TDC interrupt enable + 6 + 1 + + + RDBFIEN + RDBF interrupt enable + 5 + 1 + + + IDLEIEN + IDLE interrupt enable + 4 + 1 + + + TEN + Transmitter enable + 3 + 1 + + + REN + Receiver enable + 2 + 1 + + + RM + Receiver mute + 1 + 1 + + + SBF + Send break frame + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + ID7_4 + bit 7-4 for usart identification + 28 + 4 + + + TRPSWAP + Transmit receive pin swap + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOPBN + STOP bit num + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CLKPOL + Clock polarity + 10 + 1 + + + CLKPHA + Clock phase + 9 + 1 + + + LBCP + Last bit clock pulse + 8 + 1 + + + BFIEN + Break frame interrupt enable + 6 + 1 + + + BFBN + Break frame bit num + 5 + 1 + + + IDBN + Identification bit num + 4 + 1 + + + ID3_0 + bit 3-0 for usart identification + 0 + 4 + + + + + CTRL3 + CTRL3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + DEP + DE polarity selection + 15 + 1 + + + RS485EN + RS485 enable + 14 + 1 + + + CTSCFIEN + CTSCF interrupt enable + 10 + 1 + + + CTSEN + CTS enable + 9 + 1 + + + RTSEN + RTS enable + 8 + 1 + + + DMATEN + DMA transmitter enable + 7 + 1 + + + DMAREN + DMA receiver enable + 6 + 1 + + + SCMEN + Smartcard mode enable + 5 + 1 + + + SCNACKEN + Smartcard NACK enable + 4 + 1 + + + SLBEN + Single line bidirectional half-duplex enable + 3 + 1 + + + IRDALP + IrDA low-power mode + 2 + 1 + + + IRDAEN + IrDA enable + 1 + 1 + + + ERRIEN + Error interrupt enable + 0 + 1 + + + + + GDIV + GDIV + Guard time and division register + 0x18 + 0x20 + read-write + 0x0000 + + + SCGT + Smart card guard time value + 8 + 8 + + + ISDIV + IrDA/smartcard division value + 0 + 8 + + + + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + USART6 + 0x40011400 + + USART6 + USART6 global interrupt + 71 + + + + ADC1 + Analog to digital converter + ADC + 0x40012000 + + 0x0 + 0x100 + registers + + + ADC + ADC1 global interrupt + 18 + + + + STS + STS + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + RDY + ADC ready to conversion flag + 6 + 1 + read-only + + + OCCO + Ordinary channel conversion overflow flag + 5 + 1 + + + OCCS + Ordinary channel conversion start flag + 4 + 1 + + + PCCS + Preempted channel conversion start flag + 3 + 1 + + + PCCE + Preempted channels conversion end flag + 2 + 1 + + + OCCE + Ordinary channels conversion end flag + 1 + 1 + + + VMOR + Voltage monitoring out of range flag + 0 + 1 + + + + + CTRL1 + CTRL1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OCCOIEN + Ordinary channel conversion overflow interrupt enable + 26 + 1 + + + CRSEL + Conversion resolution select + 24 + 2 + + + OCVMEN + Voltage monitoring enable on ordinary channels + 23 + 1 + + + PCVMEN + Voltage monitoring enable on preempted channels + 22 + 1 + + + OCPCNT + Partitioned mode conversion count of ordinary channels + 13 + 3 + + + PCPEN + Partitioned mode enable on preempted channels + 12 + 1 + + + OCPEN + Partitioned mode enable on ordinary channels + 11 + 1 + + + PCAUTOEN + Preempted group automatic conversion enable after ordinary group + 10 + 1 + + + VMSGEN + Voltage monitoring enable on a single channel + 9 + 1 + + + SQEN + Sequence mode enable + 8 + 1 + + + PCCEIEN + Conversion end interrupt enable for preempted channels + 7 + 1 + + + VMORIEN + Voltage monitoring out of range interrupt enable + 6 + 1 + + + OCCEIEN + Ordinary channel conversion end interrupt enable + 5 + 1 + + + VMCSEL + Voltage monitoring channel select + 0 + 5 + + + + + CTRL2 + CTRL2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + OCTESEL_H + High bit of trigger event select for ordinary channels conversion + 31 + 1 + + + OCSWTRG + Ordinary channel software conversion trigger + 30 + 1 + + + OCETE + Ordinary channel external trigger edge select + 28 + 2 + + + OCTESEL_L + Low bit of trigger event select for ordinary channels conversion + 24 + 4 + + + PCTESEL_H + High bit of trigger event select for preempted channels conversion + 23 + 1 + + + PCSWTRG + Preempted channel software conversion trigger + 22 + 1 + + + PCETE + Preempted channel external trigger edge select + 20 + 2 + + + PCTESEL_L + Low bit of trigger event select for preempted channels conversion + 16 + 4 + + + DTALIGN + Data alignment + 11 + 1 + + + EOCSFEN + Each ordinary channel conversion set OCCE flag enable + 10 + 1 + + + OCDRCEN + Ordinary channel DMA request continuation enable for independent mode + 9 + 1 + + + OCDMAEN + Ordinary channel DMA transfer enable for independent mode + 8 + 1 + + + ADABRT + ADC conversion abort + 4 + 1 + + + ADCALINIT + Initialize A/D calibration + 3 + 1 + + + ADCAL + A/D Calibration + 2 + 1 + + + RPEN + Repeat mode enable + 1 + 1 + + + ADCEN + A/D converter enable + 0 + 1 + + + + + SPT1 + SPT1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + CSPT18 + Selection sample time of channel ADC_IN18 + 24 + 3 + + + CSPT17 + Selection sample time of channel ADC_IN17 + 21 + 3 + + + CSPT16 + Selection sample time of channel ADC_IN16 + 18 + 3 + + + CSPT15 + Selection sample time of channel ADC_IN15 + 15 + 3 + + + CSPT14 + Selection sample time of channel ADC_IN14 + 12 + 3 + + + CSPT13 + Selection sample time of channel ADC_IN13 + 9 + 3 + + + CSPT12 + Selection sample time of channel ADC_IN12 + 6 + 3 + + + CSPT11 + Selection sample time of channel ADC_IN11 + 3 + 3 + + + CSPT10 + Selection sample time of channel ADC_IN10 + 0 + 3 + + + + + SPT2 + SPT2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + CSPT9 + Selection sample time of channel ADC_IN9 + 27 + 3 + + + CSPT8 + Selection sample time of channel ADC_IN8 + 24 + 3 + + + CSPT7 + Selection sample time of channel ADC_IN7 + 21 + 3 + + + CSPT6 + Selection sample time of channel ADC_IN6 + 18 + 3 + + + CSPT5 + Selection sample time of channel ADC_IN5 + 15 + 3 + + + CSPT4 + Selection sample time of channel ADC_IN4 + 12 + 3 + + + CSPT3 + Selection sample time of channel ADC_IN3 + 9 + 3 + + + CSPT2 + Selection sample time of channel ADC_IN2 + 6 + 3 + + + CSPT1 + Selection sample time of channel ADC_IN1 + 3 + 3 + + + CSPT0 + Selection sample time of channel ADC_IN0 + 0 + 3 + + + + + PCDTO1 + PCDTO1 + Preempted channel 1 data offset register + 0x14 + 0x20 + read-write + 0x00000000 + + + PCDTO1 + Data offset for Preempted channel 1 + 0 + 12 + + + + + PCDTO2 + PCDTO2 + Preempted channel 2 data offset register + 0x18 + 0x20 + read-write + 0x00000000 + + + PCDTO2 + Data offset for Preempted channel 2 + 0 + 12 + + + + + PCDTO3 + PCDTO3 + Preempted channel 3 data offset register + 0x1C + 0x20 + read-write + 0x00000000 + + + PCDTO3 + Data offset for Preempted channel 3 + 0 + 12 + + + + + PCDTO4 + PCDTO4 + Preempted channel 4 data offset register + 0x20 + 0x20 + read-write + 0x00000000 + + + PCDTO4 + Data offset for Preempted channel 4 + 0 + 12 + + + + + VMHB + VMHB + Voltage monitoring high boundary register + 0x24 + 0x20 + read-write + 0x00000FFF + + + VMHB + Voltage monitoring high boundary + 0 + 12 + + + + + VMLB + VMLB + Voltage monitoring low boundary register + 0x28 + 0x20 + read-write + 0x00000000 + + + VMLB + Voltage monitoring low boundary + 0 + 12 + + + + + OSQ1 + OSQ1 + Ordinary sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + OCLEN + Ordinary conversion sequence length + 20 + 4 + + + OSN16 + Number of 16th conversion in ordinary sequence + 15 + 5 + + + OSN15 + Number of 15th conversion in ordinary sequence + 10 + 5 + + + OSN14 + Number of 14th conversion in ordinary sequence + 5 + 5 + + + OSN13 + Number of 13th conversion in ordinary sequence + 0 + 5 + + + + + OSQ2 + OSQ2 + Ordinary sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + OSN12 + Number of 12th conversion in ordinary sequence + 25 + 5 + + + OSN11 + Number of 11th conversion in ordinary sequence + 20 + 5 + + + OSN10 + Number of 10th conversion in ordinary sequence + 15 + 5 + + + OSN9 + Number of 8th conversion in ordinary sequence + 10 + 5 + + + OSN8 + Number of 7th conversion in ordinary sequence + 5 + 5 + + + OSN7 + Number of 13th conversion in ordinary sequence + 0 + 5 + + + + + OSQ3 + OSQ3 + Ordinary sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + OSN6 + Number of 6th conversion in ordinary sequence + 25 + 5 + + + OSN5 + Number of 5th conversion in ordinary sequence + 20 + 5 + + + OSN4 + Number of 4th conversion in ordinary sequence + 15 + 5 + + + OSN3 + number of 3rd conversion in ordinary sequence + 10 + 5 + + + OSN2 + Number of 2nd conversion in ordinary sequence + 5 + 5 + + + OSN1 + Number of 1st conversion in ordinary sequence + 0 + 5 + + + + + PSQ + PSQ + Preempted sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + PCLEN + Preempted conversion sequence length + 20 + 2 + + + PSN4 + Number of 4th conversion in Preempted sequence + 15 + 5 + + + PSN3 + Number of 3rd conversion in Preempted sequence + 10 + 5 + + + PSN2 + Number of 2nd conversion in Preempted sequence + 5 + 5 + + + PSN1 + Number of 1st conversion in Preempted sequence + 0 + 5 + + + + + PDT1 + PDT1 + Preempted data register 1 + 0x3C + 0x20 + read-only + 0x00000000 + + + PDT1 + Preempted data + 0 + 16 + + + + + PDT2 + PDT2 + Preempted data register 2 + 0x40 + 0x20 + read-only + 0x00000000 + + + PDT2 + Preempted data + 0 + 16 + + + + + PDT3 + PDT3 + Preempted data register 3 + 0x44 + 0x20 + read-only + 0x00000000 + + + PDT3 + Preempted data + 0 + 16 + + + + + PDT4 + PDT4 + Preempted data register 4 + 0x48 + 0x20 + read-only + 0x00000000 + + + PDT4 + Preempted data + 0 + 16 + + + + + ODT + ODT + Ordinary data register + 0x4C + 0x20 + read-only + 0x00000000 + + + ODT + Conversion data of ordinary channel + 0 + 16 + + + + + OVSP + OVSP + oversampling register + 0x80 + 0x20 + read-write + 0x00000000 + + + OOSRSEL + Ordinary oversampling recovery mode select + 10 + 1 + + + OOSTREN + Ordinary oversampling trigger mode enable + 9 + 1 + + + OSSSEL + Oversampling shift select + 5 + 4 + + + OSRSEL + Oversampling ratio select + 2 + 3 + + + POSEN + Preempted oversampling enable + 1 + 1 + + + OOSEN + Ordinary oversampling enable + 0 + 1 + + + + + CALVAL + CALVAL + Calibration value register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CALVAL + A/D Calibration value + 0 + 7 + + + + + + + ADC2 + 0x40012100 + + ADC + ADC2 global interrupts + 18 + + + + ADC3 + 0x40012200 + + ADC + ADC3 global interrupts + 18 + + + + ADCCOM + ADC common area + ADC + 0x40012300 + + 0x0 + 0x100 + registers + + + + CSTS + CSTS + Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + RDY3 + ADC ready to conversion flag of ADC3 + 22 + 1 + + + OCCO3 + Ordinary channel conversion overflow flag of ADC3 + 21 + 1 + + + OCCS3 + Ordinary channel conversion start flag of ADC3 + 20 + 1 + + + PCCS3 + Preempted channel conversion start flag of ADC3 + 19 + 1 + + + PCCE3 + Preempted channels conversion end flag of ADC3 + 18 + 1 + + + OCCE3 + Ordinary channels conversion end flag of ADC3 + 17 + 1 + + + VMOR3 + Voltage monitoring out of range flag of ADC3 + 16 + 1 + + + RDY2 + ADC ready to conversion flag of ADC2 + 14 + 1 + + + OCCO2 + Ordinary channel conversion overflow flag of ADC2 + 13 + 1 + + + OCCS2 + Ordinary channel conversion start flag of ADC2 + 12 + 1 + + + PCCS2 + Preempted channel conversion start flag of ADC2 + 11 + 1 + + + PCCE2 + Preempted channels conversion end flag of ADC2 + 10 + 1 + + + OCCE2 + Ordinary channels conversion end flag of ADC2 + 9 + 1 + + + VMOR2 + Voltage monitoring out of range flag of ADC2 + 8 + 1 + + + RDY1 + ADC ready to conversion flag of ADC1 + 6 + 1 + + + OCCO1 + Ordinary channel conversion overflow flag of ADC1 + 5 + 1 + + + OCCS1 + Ordinary channel conversion start flag of ADC1 + 4 + 1 + + + PCCS1 + Preempted channel conversion start flag of ADC1 + 3 + 1 + + + PCCE1 + Preempted channels conversion end flag of ADC1 + 2 + 1 + + + OCCE1 + Ordinary channels conversion end flag of ADC1 + 1 + 1 + + + VMOR1 + Voltage monitoring out of range flag of ADC1 + 0 + 1 + + + + + CCTRL + CCTRL + Common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + MSDMASEL_H + High bit of ordinary channel DMA transfer mode select for master slave mode + 28 + 1 + + + ITSRVEN + Internal temperature sensor and VINTRV enable + 23 + 1 + + + VBATEN + VBAT enable + 22 + 1 + + + ADCDIV + ADC division + 16 + 4 + + + MSDMASEL_L + Low bit of ordinary channel DMA transfer mode select for master slave mode + 14 + 2 + + + MSDRCEN + Ordinary channel DMA request continuation enable for master slave mode + 13 + 1 + + + ASISEL + Adjacent ADC sampling interval select for ordinary shifting mode + 8 + 4 + + + MSSEL + Master slave mode select + 0 + 5 + + + + + CODT + CODT + Common Ordinary data register + 0x8 + 0x20 + read-only + 0x00000000 + + + CODTH + Ordinary conversion high halfword data for master slave mode + 16 + 16 + + + CODTL + Ordinary conversion low halfword data for master slave mode + 0 + 16 + + + + + + + CAN1 + Can controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupt + 19 + + + CAN1_RX0 + CAN1 RX0 interrupt + 20 + + + CAN_RX1 + CAN1 RX1 interrupt + 21 + + + CAN_SE + CAN1 SE interrupt + 22 + + + + MCTRL + MCTRL + Main control register + 0x0 + 0x20 + read-write + 0x00010002 + + + PTD + Prohibit transmission when debug + 16 + 1 + + + SPRST + Software partial reset + 15 + 1 + + + TTCEN + Time triggered communication mode enable + 7 + 1 + + + AEBOEN + Automatic exit bus-off enable + 6 + 1 + + + AEDEN + Automatic exit doze mode enable + 5 + 1 + + + PRSFEN + Prohibit retransmission when sending fails enable + 4 + 1 + + + MDRSEL + Message discarding rule select when overflow + 3 + 1 + + + MMSSR + Multiple message sending sequence rule + 2 + 1 + + + DZEN + Doze mode enable + 1 + 1 + + + FZEN + Freeze mode enable + 0 + 1 + + + + + MSTS + MSTS + Main status register + 0x4 + 0x20 + 0x00000C02 + + + REALRX + Real time level of RX pin + 11 + 1 + read-only + + + LSAMPRX + Last sample level of RX pin + 10 + 1 + read-only + + + CURS + Currently receiving status + 9 + 1 + read-only + + + CUSS + Currently sending status + 8 + 1 + read-only + + + EDZIF + Enter doze mode interrupt flag + 4 + 1 + read-write + + + QDZIF + Quit doze mode interrupt flag + 3 + 1 + read-write + + + EOIF + Error occur Interrupt flag + 2 + 1 + read-write + + + DZC + Doze mode confirm + 1 + 1 + read-only + + + FZC + Freeze mode confirm + 0 + 1 + read-only + + + + + TSTS + TSTS + Transmit status register + 0x8 + 0x20 + 0x1C000000 + + + TM2LPF + Transmit mailbox 2 lowest priority flag + 31 + 1 + read-only + + + TM1LPF + Transmit mailbox 1 lowest priority flag + 30 + 1 + read-only + + + TM0LPF + Transmit mailbox 0 lowest priority flag + 29 + 1 + read-only + + + TM2EF + Transmit mailbox 2 empty flag + 28 + 1 + read-only + + + TM1EF + Transmit mailbox 1 empty flag + 27 + 1 + read-only + + + TM0EF + Transmit mailbox 0 empty flag + 26 + 1 + read-only + + + TMNR + Transmit Mailbox number record + 24 + 2 + read-only + + + TM2CT + Transmit mailbox 2 cancel transmission + 23 + 1 + read-write + + + TM2TEF + Transmit mailbox 2 transmission error flag + 19 + 1 + read-write + + + TM2ALF + Transmit mailbox 2 arbitration lost flag + 18 + 1 + read-write + + + TM2TSF + Transmit mailbox 2 transmission success flag + 17 + 1 + read-write + + + TM2TCF + transmit mailbox 2 transmission complete flag + 16 + 1 + read-write + + + TM1CT + Transmit mailbox 1 cancel transmission + 15 + 1 + read-write + + + TM1TEF + Transmit mailbox 1 transmission error flag + 11 + 1 + read-write + + + TM1ALF + Transmit mailbox 1 arbitration lost flag + 10 + 1 + read-write + + + TM1TSF + Transmit mailbox 1 transmission success flag + 9 + 1 + read-write + + + TM1TCF + Transmit mailbox 1 transmission complete flag + 8 + 1 + read-write + + + TM0CT + Transmit mailbox 0 cancel transmission + 7 + 1 + read-write + + + TM0TEF + Transmit mailbox 0 transmission error flag + 3 + 1 + read-write + + + TM0ALF + Transmit mailbox 0 arbitration lost flag + 2 + 1 + read-write + + + TM0TSF + Transmit mailbox 0 transmission success flag + 1 + 1 + read-write + + + TM0TCF + Transmit mailbox 0 transmission complete flag + 0 + 1 + read-write + + + + + RF0 + RF0 + Receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RF0R + Receive FIFO 0 release + 5 + 1 + read-write + + + RF0OF + Receive FIFO 0 overflow flag + 4 + 1 + read-write + + + RF0FF + Receive FIFO 0 full flag + 3 + 1 + read-write + + + RF0MN + Receive FIFO 0 message num + 0 + 2 + read-only + + + + + RF1 + RF1 + Receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RF1R + Receive FIFO 1 release + 5 + 1 + read-write + + + RF1OF + Receive FIFO 1 overflow flag + 4 + 1 + read-write + + + RF1FF + Receive FIFO 1 full flag + 3 + 1 + read-write + + + RF1MN + Receive FIFO 1 message num + 0 + 2 + read-only + + + + + INTEN + INTEN + Interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + EDZIEN + Enter doze mode interrupt enable + 17 + 1 + + + QDZIEN + Quit doze mode interrupt enable + 16 + 1 + + + EOIEN + Error occur interrupt enable + 15 + 1 + + + ETRIEN + Error type record interrupt enable + 11 + 1 + + + BOIEN + Bus-off interrupt enable + 10 + 1 + + + EPIEN + Error passive interrupt enable + 9 + 1 + + + EAIEN + Error active interrupt enable + 8 + 1 + + + RF1OIEN + Receive FIFO 1 overflow interrupt enable + 6 + 1 + + + RF1FIEN + Receive FIFO 1 full interrupt enable + 5 + 1 + + + RF1MIEN + FIFO 1 receive message interrupt enable + 4 + 1 + + + RF0OIEN + Receive FIFO 0 overflow interrupt enable + 3 + 1 + + + RF0FIEN + Receive FIFO 0 full interrupt enable + 2 + 1 + + + RF0MIEN + FIFO 0 receive message interrupt enable + 1 + 1 + + + TCIEN + Transmission complete interrupt enable + 0 + 1 + + + + + ESTS + ESTS + Error status register + 0x18 + 0x20 + 0x00000000 + + + REC + Receive error counter + 24 + 8 + read-only + + + TEC + Transmit error counter + 16 + 8 + read-only + + + ETR + Error type record + 4 + 3 + read-write + + + BOF + Bus-off flag + 2 + 1 + read-only + + + EPF + Error passive flag + 1 + 1 + read-only + + + EAF + Error active flag + 0 + 1 + read-only + + + + + BTMG + BTMG + Bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + LOEN + Listen-Only mode + 31 + 1 + + + LBEN + Loop back mode + 30 + 1 + + + RSAW + Resynchronization adjust width + 24 + 2 + + + BTS2 + Bit time segment 2 + 20 + 3 + + + BTS1 + Bit time segment 1 + 16 + 4 + + + BRDIV + Baud rate division + 0 + 12 + + + + + TMI0 + TMI0 + Transmit mailbox 0 identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC0 + TMC0 + Transmit mailbox 0 data length and time stamp register + 0x184 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL0 + TMDTL0 + Transmit mailbox 0 low byte data register + 0x188 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH0 + TMDTH0 + Transmit mailbox 0 high byte data register + 0x18C + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + TMI1 + TMI1 + Transmit mailbox 1 identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC1 + TMC1 + Transmit mailbox 1 data length and time stamp register + 0x194 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL1 + TMDTL1 + Transmit mailbox 1 low byte data register + 0x198 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH1 + TMDTH1 + Transmit mailbox 1 high byte data register + 0x19C + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + TMI2 + TMI2 + Transmit mailbox 2 identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC2 + TMC2 + Transmit mailbox 2 data length and time stamp register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL2 + TMDTL2 + Transmit mailbox 2 low byte data register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH2 + TMDTH2 + Transmit mailbox 2 high byte data register + 0x1AC + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + RFI0 + RFI0 + Receive FIFO 0 register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + RFSID + Receive FIFO standard identifier or receive FIFO extended identifier + 21 + 11 + + + RFEID + Receive FIFO extended identifier + 3 + 18 + + + RFIDI + Receive FIFO identifier type indication + 2 + 1 + + + RFFRI + Receive FIFO frame type indication + 1 + 1 + + + + + RFC0 + RFC0 + Receive FIFO 0 data length and time stamp register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + RFTS + Receive FIFO time stamp + 16 + 16 + + + RFFMN + Receive FIFO filter match number + 8 + 8 + + + RFDTL + Receive FIFO data length + 0 + 4 + + + + + RFDTL0 + RFDTL0 + Receive FIFO 0 low byte data register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + RFDT3 + Receive FIFO data byte 3 + 24 + 8 + + + RFDT2 + Receive FIFO data byte 2 + 16 + 8 + + + RFDT1 + Receive FIFO data byte 1 + 8 + 8 + + + RFDT0 + Receive FIFO data byte 0 + 0 + 8 + + + + + RFDTH0 + RFDTH0 + Receive FIFO 0 high byte data register + 0x1BC + 0x20 + read-only + 0x00000000 + + + RFDT7 + Receive FIFO data byte 7 + 24 + 8 + + + RFDT6 + Receive FIFO data byte 6 + 16 + 8 + + + RFDT5 + Receive FIFO data byte 5 + 8 + 8 + + + RFDT4 + Receive FIFO data byte 4 + 0 + 8 + + + + + RFI1 + RFI1 + Receive FIFO 1 register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + RFSID + Receive FIFO standard identifier or receive FIFO extended identifier + 21 + 11 + + + RFEID + Receive FIFO extended identifier + 3 + 18 + + + RFIDI + Receive FIFO identifier type indication + 2 + 1 + + + RFFRI + Receive FIFO frame type indication + 1 + 1 + + + + + RFC1 + RFC1 + Receive FIFO 1 data length and time stamp register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + RFTS + Receive FIFO time stamp + 16 + 16 + + + RFFMN + Receive FIFO filter match number + 8 + 8 + + + RFDTL + Receive FIFO data length + 0 + 4 + + + + + RFDTL1 + RFDTL1 + Receive FIFO 1 low byte data register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + RFDT3 + Receive FIFO data byte 3 + 24 + 8 + + + RFDT2 + Receive FIFO data byte 2 + 16 + 8 + + + RFDT1 + Receive FIFO data byte 1 + 8 + 8 + + + RFDT0 + Receive FIFO data byte 0 + 0 + 8 + + + + + RFDTH1 + RFDTH1 + Receive FIFO 1 high byte data register + 0x1CC + 0x20 + read-only + 0x00000000 + + + RFDT7 + Receive FIFO data byte 7 + 24 + 8 + + + RFDT6 + Receive FIFO data byte 6 + 16 + 8 + + + RFDT5 + Receive FIFO data byte 5 + 8 + 8 + + + RFDT4 + Receive FIFO data byte 4 + 0 + 8 + + + + + FCTRL + FCTRL + Filter control register + 0x200 + 0x20 + read-write + 0x00000000 + + + FCS + Filters configure switch + 0 + 1 + + + + + FMCFG + FMCFG + Filter mode config register + 0x204 + 0x20 + read-write + 0x00000000 + + + FMSEL0 + Filter mode select + 0 + 1 + + + FMSEL1 + Filter mode select + 1 + 1 + + + FMSEL2 + Filter mode select + 2 + 1 + + + FMSEL3 + Filter mode select + 3 + 1 + + + FMSEL4 + Filter mode select + 4 + 1 + + + FMSEL5 + Filter mode select + 5 + 1 + + + FMSEL6 + Filter mode select + 6 + 1 + + + FMSEL7 + Filter mode select + 7 + 1 + + + FMSEL8 + Filter mode select + 8 + 1 + + + FMSEL9 + Filter mode select + 9 + 1 + + + FMSEL10 + Filter mode select + 10 + 1 + + + FMSEL11 + Filter mode select + 11 + 1 + + + FMSEL12 + Filter mode select + 12 + 1 + + + FMSEL13 + Filter mode select + 13 + 1 + + + FMSEL14 + Filter mode select + 14 + 1 + + + FMSEL15 + Filter mode select + 15 + 1 + + + FMSEL16 + Filter mode select + 16 + 1 + + + FMSEL17 + Filter mode select + 17 + 1 + + + FMSEL18 + Filter mode select + 18 + 1 + + + FMSEL19 + Filter mode select + 19 + 1 + + + FMSEL20 + Filter mode select + 20 + 1 + + + FMSEL21 + Filter mode select + 21 + 1 + + + FMSEL22 + Filter mode select + 22 + 1 + + + FMSEL23 + Filter mode select + 23 + 1 + + + FMSEL24 + Filter mode select + 24 + 1 + + + FMSEL25 + Filter mode select + 25 + 1 + + + FMSEL26 + Filter mode select + 26 + 1 + + + FMSEL27 + Filter mode select + 27 + 1 + + + + + FBWCFG + FBWCFG + Filter bit width config register + 0x20C + 0x20 + read-write + 0x00000000 + + + FBWSEL0 + Filter bit width select + 0 + 1 + + + FBWSEL1 + Filter bit width select + 1 + 1 + + + FBWSEL2 + Filter bit width select + 2 + 1 + + + FBWSEL3 + Filter bit width select + 3 + 1 + + + FBWSEL4 + Filter bit width select + 4 + 1 + + + FBWSEL5 + Filter bit width select + 5 + 1 + + + FBWSEL6 + Filter bit width select + 6 + 1 + + + FBWSEL7 + Filter bit width select + 7 + 1 + + + FBWSEL8 + Filter bit width select + 8 + 1 + + + FBWSEL9 + Filter bit width select + 9 + 1 + + + FBWSEL10 + Filter bit width select + 10 + 1 + + + FBWSEL11 + Filter bit width select + 11 + 1 + + + FBWSEL12 + Filter bit width select + 12 + 1 + + + FBWSEL13 + Filter bit width select + 13 + 1 + + + FBWSEL14 + Filter bit width select + 14 + 1 + + + FBWSEL15 + Filter bit width select + 15 + 1 + + + FBWSEL16 + Filter bit width select + 16 + 1 + + + FBWSEL17 + Filter bit width select + 17 + 1 + + + FBWSEL18 + Filter bit width select + 18 + 1 + + + FBWSEL19 + Filter bit width select + 19 + 1 + + + FBWSEL20 + Filter bit width select + 20 + 1 + + + FBWSEL21 + Filter bit width select + 21 + 1 + + + FBWSEL22 + Filter bit width select + 22 + 1 + + + FBWSEL23 + Filter bit width select + 23 + 1 + + + FBWSEL24 + Filter bit width select + 24 + 1 + + + FBWSEL25 + Filter bit width select + 25 + 1 + + + FBWSEL26 + Filter bit width select + 26 + 1 + + + FBWSEL27 + Filter bit width select + 27 + 1 + + + + + FRF + FRF + Filter related FIFO register + 0x214 + 0x20 + read-write + 0x00000000 + + + FRFSEL0 + Filter relation FIFO select + 0 + 1 + + + FRFSEL1 + Filter relation FIFO select + 1 + 1 + + + FRFSEL2 + Filter relation FIFO select + 2 + 1 + + + FRFSEL3 + Filter relation FIFO select + 3 + 1 + + + FRFSEL4 + Filter relation FIFO select + 4 + 1 + + + FRFSEL5 + Filter relation FIFO select + 5 + 1 + + + FRFSEL6 + Filter relation FIFO select + 6 + 1 + + + FRFSEL7 + Filter relation FIFO select + 7 + 1 + + + FRFSEL8 + Filter relation FIFO select + 8 + 1 + + + FRFSEL9 + Filter relation FIFO select + 9 + 1 + + + FRFSEL10 + Filter relation FIFO select + 10 + 1 + + + FRFSEL11 + Filter relation FIFO select + 11 + 1 + + + FRFSEL12 + Filter relation FIFO select + 12 + 1 + + + FRFSEL13 + Filter relation FIFO select + 13 + 1 + + + FRFSEL14 + Filter relation FIFO select + 14 + 1 + + + FRFSEL15 + Filter relation FIFO select + 15 + 1 + + + FRFSEL16 + Filter relation FIFO select + 16 + 1 + + FRFSEL17 + Filter relation FIFO select + 17 + 1 + + + FRFSEL18 + Filter relation FIFO select + 18 + 1 + + + FRFSEL19 + Filter relation FIFO select + 19 + 1 + + + FRFSEL20 + Filter relation FIFO select + 20 + 1 + + + FRFSEL21 + Filter relation FIFO select + 21 + 1 + + + FRFSEL22 + Filter relation FIFO select + 22 + 1 + + + FRFSEL23 + Filter relation FIFO select + 23 + 1 + + + FRFSEL24 + Filter relation FIFO select + 24 + 1 + + + FRFSEL25 + Filter relation FIFO select + 25 + 1 + + + FRFSEL26 + Filter relation FIFO select + 26 + 1 + + + FRFSEL27 + Filter relation FIFO select + 27 + 1 + + + + + FACFG + FACFG + Filter activate configuration register + 0x21C + 0x20 + read-write + 0x00000000 + + + FAEN0 + Filter activate enable + 0 + 1 + + + FAEN1 + Filter activate enable + 1 + 1 + + + FAEN2 + Filter activate enable + 2 + 1 + + + FAEN3 + Filter activate enable + 3 + 1 + + + FAEN4 + Filter activate enable + 4 + 1 + + + FAEN5 + Filter activate enable + 5 + 1 + + + FAEN6 + Filter activate enable + 6 + 1 + + + FAEN7 + Filter activate enable + 7 + 1 + + + FAEN8 + Filter activate enable + 8 + 1 + + + FAEN9 + Filter activate enable + 9 + 1 + + + FAEN10 + Filter activate enable + 10 + 1 + + + FAEN11 + Filter activate enable + 11 + 1 + + + FAEN12 + Filter activate enable + 12 + 1 + + + FAEN13 + Filter activate enable + 13 + 1 + + + FAEN14 + Filter activate enable + 14 + 1 + + FAEN15 + Filter activate enable + 15 + 1 + + + FAEN16 + Filter activate enable + 16 + 1 + + + FAEN17 + Filter activate enable + 17 + 1 + + + FAEN18 + Filter activate enable + 18 + 1 + + + FAEN19 + Filter activate enable + 19 + 1 + + + FAEN20 + Filter activate enable + 20 + 1 + + + FAEN21 + Filter activate enable + 21 + 1 + + + FAEN22 + Filter activate enable + 22 + 1 + + + FAEN23 + Filter activate enable + 23 + 1 + + + FAEN24 + Filter activate enable + 24 + 1 + + + FAEN25 + Filter activate enable + 25 + 1 + + + FAEN26 + Filter activate enable + 26 + 1 + + + FAEN27 + Filter activate enable + 27 + 1 + + + + + F0FB1 + F0FB1 + Filter bank 0 filtrate bit register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F0FB2 + F0FB2 + Filter bank 0 filtrate bit register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F1FB1 + F1FB1 + Filter bank 1 filtrate bit register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F1FB2 + F1FB2 + Filter bank 1 filtrate bit register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F2FB1 + F2FB1 + Filter bank 2 filtrate bit register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F2FB2 + F2FB2 + Filter bank 2 filtrate bit register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F3FB1 + F3FB1 + Filter bank 3 filtrate bit register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F3FB2 + F3FB2 + Filter bank 3 filtrate bit register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F4FB1 + F4FB1 + Filter bank 4 filtrate bit register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F4FB2 + F4FB2 + Filter bank 4 filtrate bit register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F5FB1 + F5FB1 + Filter bank 5 filtrate bit register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F5FB2 + F5FB2 + Filter bank 5 filtrate bit register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F6FB1 + F6FB1 + Filter bank 6 filtrate bit register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F6FB2 + F6FB2 + Filter bank 6 filtrate bit register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + + F7FB1 + F7FB1 + Filter bank 7 filtrate bit register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F7FB2 + F7FB2 + Filter bank 7 filtrate bit register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F8FB1 + F8FB1 + Filter bank 8 filtrate bit register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F8FB2 + F8FB2 + Filter bank 8 filtrate bit register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F9FB1 + F9FB1 + Filter bank 9 filtrate bit register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F9FB2 + F9FB2 + Filter bank 9 filtrate bit register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F10FB1 + F10FB1 + Filter bank 10 filtrate bit register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F10FB2 + F10FB2 + Filter bank 10 filtrate bit register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F11FB1 + F11FB1 + Filter bank 11 filtrate bit register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F11FB2 + F11FB2 + Filter bank 11 filtrate bit register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F12FB1 + F12FB1 + Filter bank 12 filtrate bit register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F12FB2 + F12FB2 + Filter bank 12 filtrate bit register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F13FB1 + F13FB1 + Filter bank 13 filtrate bit register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F13FB2 + F13FB2 + Filter bank 13 filtrate bit register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F14FB1 + F14FB1 + Filter bank 14 filtrate bit register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F14FB2 + F14FB2 + Filter bank 14 filtrate bit register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F15FB1 + F15FB1 + Filter bank 15 filtrate bit register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F15FB2 + F15FB2 + Filter bank 15 filtrate bit register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F16FB1 + F16FB1 + Filter bank 16 filtrate bit register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F16FB2 + F16FB2 + Filter bank 16 filtrate bit register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F17FB1 + F17FB1 + Filter bank 17 filtrate bit register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F17FB2 + F17FB2 + Filter bank 17 filtrate bit register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F18FB1 + F18FB1 + Filter bank 18 filtrate bit register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F18FB2 + F18FB2 + Filter bank 18 filtrate bit register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F19FB1 + F19FB1 + Filter bank 19 filtrate bit register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F19FB2 + F19FB2 + Filter bank 19 filtrate bit register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F20FB1 + F20FB1 + Filter bank 20 filtrate bit register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F20FB2 + F20FB2 + Filter bank 20 filtrate bit register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F21FB1 + F21FB1 + Filter bank 21 filtrate bit register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F21FB2 + F21FB2 + Filter bank 21 filtrate bit register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F22FB1 + F22FB1 + Filter bank 22 filtrate bit register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F22FB2 + F22FB2 + Filter bank 22 filtrate bit register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F23FB1 + F23FB1 + Filter bank 23 filtrate bit register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F23FB2 + F23FB2 + Filter bank 23 filtrate bit register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F24FB1 + F24FB1 + Filter bank 24 filtrate bit register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F24FB2 + F24FB2 + Filter bank 24 filtrate bit register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F25FB1 + F25FB1 + Filter bank 25 filtrate bit register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F25FB2 + F25FB2 + Filter bank 25 filtrate bit register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F26FB1 + F26FB1 + Filter bank 26 filtrate bit register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F26FB2 + F26FB2 + Filter bank 26 filtrate bit register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F27FB1 + F27FB1 + Filter bank 27 filtrate bit register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F27FB2 + F27FB2 + Filter bank 27 filtrate bit register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupt + 63 + + + CAN2_RX0 + CAN2 RX0 interrupt + 64 + + + CAN2_RX1 + CAN2 RX1 interrupt + 65 + + + CAN2_SE + CAN2 SE interrupt + 66 + + + + DAC + Digital to analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CTRL + CTRL + Control register (DAC_CTRL) + 0x0 + 0x20 + read-write + 0x00000000 + + + D1EN + DAC1 enable + 0 + 1 + + + D1OBDIS + DAC1 output buffer disable + 1 + 1 + + + D1TRGEN + DAC1 trigger enable + 2 + 1 + + + D1TRGSEL + DAC1 trigger selection + 3 + 3 + + + D1NM + DAC1 noise/triangle wave generation enable + 6 + 2 + + + D1NBSEL + DAC1 mask/amplitude selector + 8 + 4 + + + D1DMAEN + DAC1 DMA enable + 12 + 1 + + + D1DMAUDRIEN + DAC1 DMA underrun interrupt enable + 13 + 1 + + + D2EN + DAC2 enable + 16 + 1 + + + D2OBDIS + DAC2 output buffer disable + 17 + 1 + + + D2TRGEN + DAC2 trigger enable + 18 + 1 + + + D2TRGSEL + DAC2 trigger selection + 19 + 3 + + + D2NM + DAC2 noise/triangle wave generation enable + 22 + 2 + + + D2NBSEL + DAC2 mask/amplitude selector + 24 + 4 + + + D2DMAEN + DAC2 DMA enable + 28 + 1 + + + D2DMAUDRIEN + DAC2 DMA underrun interrupt enable + 29 + 1 + + + + + SWTRG + SWTRG + DAC software trigger register(DAC_SWTRIGR) + 0x4 + 0x20 + write-only + 0x00000000 + + + D1SWTRG + DAC1 software trigger + 0 + 1 + + + D2SWTRG + DAC2 software trigger + 1 + 1 + + + + + D1DTH12R + D1DTH12R + DAC1 12-bit right-aligned data holding register(DAC_D1DTH12R) + 0x8 + 0x20 + read-write + 0x00000000 + + + D1DT12R + DAC1 12-bit right-aligned data + 0 + 12 + + + + + D1DTH12L + D1DTH12L + DAC1 12-bit left aligned data holding register (DAC_D1DTH12L) + 0xC + 0x20 + read-write + 0x00000000 + + + D1DT12L + DAC1 12-bit left-aligned data + 4 + 12 + + + + + D1DTH8R + D1DTH8R + DAC1 8-bit right aligned data holding register (DAC_D1DTH8R) + 0x10 + 0x20 + read-write + 0x00000000 + + + D1DT8R + DAC1 8-bit right-aligned data + 0 + 8 + + + + + D2DTH12R + D2DTH12R + DAC2 12-bit right aligned data holding register (DAC_D2DTH12R) + 0x14 + 0x20 + read-write + 0x00000000 + + + D2DT12R + DAC2 12-bit right-aligned + data + 0 + 12 + + + + + D2DTH12L + D2DTH12L + DAC2 12-bit left aligned data holding register (DAC_D2DTH12L) + 0x18 + 0x20 + read-write + 0x00000000 + + + D2DT12L + DAC2 12-bit left-aligned data + 4 + 12 + + + + + D2DTH8R + D2DTH8R + DAC2 8-bit right-aligned data holding register (DAC_D2DTH8R) + 0x1C + 0x20 + read-write + 0x00000000 + + + D2DT8R + DAC2 8-bit right-aligned + data + 0 + 8 + + + + + DDTH12R + DDTH12R + Dual DAC 12-bit right-aligned data holding register (DAC_DDTH12R), Bits 31:28 Reserved, Bits 15:12 Reserved + 0x20 + 0x20 + read-write + 0x00000000 + + + DD1DT12R + DAC1 12-bit right-aligned data + 0 + 12 + + + DD2DT12R + DAC2 12-bit right-aligned data + 16 + 12 + + + + + DDTH12L + DDTH12L + DUAL DAC 12-bit left aligned data holding register (DAC_DDTH12L), Bits 19:16 Reserved, Bits 3:0 Reserved + 0x24 + 0x20 + read-write + 0x00000000 + + + DD1DT12L + DAC1 12-bit left-aligned data + 4 + 12 + + + DD2DT12L + DAC2 12-bit right-aligned data + 20 + 12 + + + + + DDTH8R + DDTH8R + DUAL DAC 8-bit right aligned data holding register (DAC_DDTH8R), Bits 31:16 Reserved + 0x28 + 0x20 + read-write + 0x00000000 + + + DD1DT8R + DAC1 8-bit right-aligned data + 0 + 8 + + + DD2DT8R + DAC2 8-bit right-aligned data + 8 + 8 + + + + + D1ODT + D1ODT + DAC1 data output register (DAC_D1ODT) + 0x2C + 0x20 + read-only + 0x00000000 + + + D1ODT + DAC1 data output + 0 + 12 + + + + + D2ODT + D2ODT + DAC2 data output register (DAC_D2ODT) + 0x30 + 0x20 + read-only + 0x00000000 + + + D2ODT + DAC2 data output + 0 + 12 + + + + + STS + STS + DAC2 status register + (DAC_STS) + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR1 + DAC1 DMA underrun flag + 13 + 1 + + + DMAUDR2 + DAC2 DMA underrun flag + 29 + 1 + + + + + + + DEBUG + Debug support + DEBUG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + IDCODE + IDCODE + DEBUG IDCODE + 0x0 + 0x20 + read-only + 0x0 + + + PID + Product ID + 0 + 32 + + + + + CTRL + CTRL + DEBUG CTRL + 0x4 + 0x20 + read-write + 0x0 + + + SLEEP_DEBUG + SLEEP_DEBUG + 0 + 1 + + + DEEPSLEEP_DEBUG + DEEPSLEEP_DEBUG + 1 + 1 + + + STANDBY_DEBUG + STANDBY_DEBUG + 2 + 1 + + + + + APB1_PAUSE + APB1_PAUSE + DEBUG APB1 PAUSE + 0x8 + 0x20 + read-write + 0x0 + + + TMR2_PAUSE + TMR2_PAUSE + 0 + 1 + + + TMR3_PAUSE + TMR3_PAUSE + 1 + 1 + + + TMR4_PAUSE + TMR4_PAUSE + 2 + 1 + + + TMR5_PAUSE + TMR5_PAUSE + 3 + 1 + + + TMR6_PAUSE + TMR6_PAUSE + 4 + 1 + + + TMR7_PAUSE + TMR7_PAUSE + 5 + 1 + + + TMR12_PAUSE + TMR12_PAUSE + 6 + 1 + + + TMR13_PAUSE + TMR13_PAUSE + 7 + 1 + + + TMR14_PAUSE + TMR14_PAUSE + 8 + 1 + + + ERTC_PAUSE + ERTC_PAUSE + 10 + 1 + + + WWDT_PAUSE + WWDT_PAUSE + 11 + 1 + + + WDT_PAUSE + WDT_PAUSE + 12 + 1 + + + ERTC512_PAUSE + ERTC512_PAUSE + 15 + 1 + + + I2C1_SMBUS_TIMEOUT + I2C1_SMBUS_TIMEOUT + 24 + 1 + + + CAN1_PAUSE + CAN1_PAUSE + 25 + 1 + + + CAN2_PAUSE + CAN2_PAUSE + 26 + 1 + + + I2C2_SMBUS_TIMEOUT + I2C2_SMBUS_TIMEOUT + 27 + 1 + + + I2C3_SMBUS_TIMEOUT + I2C3_SMBUS_TIMEOUT + 28 + 1 + + + + + APB2_PAUSE + APB2_PAUSE + DEBUG APB2 PAUSE + 0xC + 0x20 + read-write + 0x0 + + + TMR1_PAUSE + TMR1_PAUSE + 0 + 1 + + + TMR8_PAUSE + TMR8_PAUSE + 1 + 1 + + + TMR20_PAUSE + TIM20_PAUSE + 6 + 1 + + + TMR9_PAUSE + TMR9_PAUSE + 16 + 1 + + + TMR10_PAUSE + TMR10_PAUSE + 17 + 1 + + + TMR11_PAUSE + TMR11_PAUSE + 18 + 1 + + + + + SER_ID + SER_ID + SERIES ID + 0x20 + 0x20 + read-only + 0x0 + + + REV_ID + version ID + 0 + 3 + + + SER_ID + series ID + 8 + 8 + + + + + + + UART4 + Universal asynchronous receiver transmitter + 0x40004C00 + + UART4 + UART4 global interrupt + 52 + + + + UART5 + Universal asynchronous receiver transmitter + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + UART7 + Universal asynchronous receiver transmitter + 0x40007800 + + UART7 + UART7 global interrupt + 82 + + + + UART8 + Universal asynchronous receiver transmitter + 0x40007C00 + + UART8 + UART8 global interrupt + 83 + + + + CRC + CRC calculation unit + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DT + DT + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DT + Data Register + 0 + 32 + + + + + CDT + CDT + Common data register + 0x4 + 0x20 + read-write + 0x00000000 + + + CDT + Common Data + 0 + 1 + + + + + CTRL + CTRL + Control register + 0x8 + 0x20 + read-write + 0x00000000 + + + RST + Reset bit + 0 + 1 + + + REVID + Reverse input data + 5 + 2 + + + REVOD + Reverse output data + 7 + 1 + + + + + IDT + IDT + Initial data register + 0x10 + 0x20 + read-write + 0xFFFFFFFF + + + IDT + Initial Data + 0 + 32 + + + + + + + FLASH + Flash memory controler + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + PSR + PSR + Performance selection register + 0x0 + 0x20 + 0x00000330 + + + NZW_BST_STS + Flash non-zero wait area boost status + 13 + 1 + read-only + + + NZW_BST + Flash non-zero wait area boost + 12 + 1 + read-write + + + + + UNLOCK + UNLOCK + Unlock register + 0x4 + 0x20 + write-only + 0x00000000 + + + UKVAL + Unlock key value + 0 + 32 + + + + + USD_UNLOCK + USD_UNLOCK + USD unlock register + 0x8 + 0x20 + write-only + 0x00000000 + + + USD_UKVAL + User system data Unlock key value + 0 + 32 + + + + + STS + STS + Status register + 0xC + 0x20 + 0x00000000 + + + ODF + Operate done flag + 5 + 1 + read-write + + + EPPERR + Erase/program protection error + 4 + 1 + read-write + + + PRGMERR + program error + 2 + 1 + read-write + + + OBF + Operate busy flag + 0 + 1 + read-only + + + + + CTRL + CTRL + Control register + 0x10 + 0x20 + read-write + 0x00000080 + + + FPRGM + Flash program + 0 + 1 + + + SECERS + Sector erase + 1 + 1 + + + BANKERS + Bank erase + 2 + 1 + + + BLKERS + Block erase + 3 + 1 + + + USDPRGM + User system data program + 4 + 1 + + + USDERS + User system data erase + 5 + 1 + + + ERSTR + Erasing start + 6 + 1 + + + OPLK + Operation lock + 7 + 1 + + + USDULKS + User system data unlock success + 9 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + ODFIE + Operation done flag interrupt enable + 12 + 1 + + + + + ADDR + ADDR + Address register + 0x14 + 0x20 + write-only + 0x00000000 + + + FA + Flash Address + 0 + 32 + + + + + USD + USD + User system data register + 0x1C + 0x20 + read-only + 0x03FFFFFC + + + USDERR + User system data error + 0 + 1 + + + FAP + FLASH access protection + 1 + 1 + + + nWDT_ATO_EN + WDT auto enable + 2 + 1 + + + nDEPSLP_RST + Deepsleep reset + 3 + 1 + + + nSTDBY_RST + Standby reset + 4 + 1 + + + BTOPT + boot option + 5 + 1 + + + nWDT_DEPSLP + WDT deep sleep + 7 + 1 + + + nWDT_STDBY + WDT standby + 8 + 1 + + + USER_D0 + User data 0 + 10 + 8 + + + USER_D1 + User data 1 + 18 + 8 + + + + + EPPS0 + EPPS0 + Erase/program protection status register 0 + 0x20 + 0x20 + read-only + 0xFFFFFFFF + + + EPPS + Erase/program protection status + 0 + 32 + + + + + EPPS1 + EPPS1 + Erase/program protection status register 1 + 0x2C + 0x20 + read-only + 0xFFFFFFFF + + + EPPS + Erase/program protection status + 0 + 32 + + + + + UNLOCK2 + UNLOCK2 + Unlock 2 register + 0x44 + 0x20 + write-only + 0x00000000 + + + UKVAL + Unlock key value + 0 + 32 + + + + + STS2 + STS2 + Status 2 register + 0x4C + 0x20 + 0x00000000 + + + OBF + Operate busy flag + 0 + 1 + read-only + + + PRGMERR + program error + 2 + 1 + read-write + + + EPPERR + Erase/program protection error + 4 + 1 + read-write + + + ODF + Operate done flag + 5 + 1 + read-write + + + + + CTRL2 + CTRL2 + Control 2 register + 0x50 + 0x20 + read-write + 0x00000080 + + + FPRGM + Flash program + 0 + 1 + + + SECERS + Sector erase + 1 + 1 + + + BANKERS + Bank erase + 2 + 1 + + + BLKERS + Block erase + 3 + 1 + + + ERSTR + Erasing start + 6 + 1 + + + OPLK + Operation lock + 7 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + ODFIE + Operation done flag interrupt enable + 12 + 1 + + + + + ADDR2 + ADDR2 + Address 2 register + 0x54 + 0x20 + write-only + 0x00000000 + + + FA + Flash Address + 0 + 32 + + + + + CONTR + CONTR + Flash continue read register + 0x58 + 0x20 + read-write + 0x00000080 + + + FCONTR_EN + Flash continue read enable + 31 + 1 + + + + + DIVR + DIVR + Flash divider register + 0x60 + 0x20 + 0x00000022 + + + FDIV + Flash divider + 0 + 2 + read-write + + + FDIV_STS + Flash divider status + 4 + 2 + read-only + + + + + SLIB_STS2 + SLIB_STS2 + sLib status 2 register + 0xC8 + 0x20 + 0x0000FFFF + + + SLIB_INST_SS + sLib instruction start sector + 0 + 16 + read-only + + + + + SLIB_STS0 + SLIB_STS0 + sLib status 0 register + 0xCC + 0x20 + 0x00000000 + + + SLIB_ENF + sLib enabled flag + 3 + 1 + read-only + + + + + SLIB_STS1 + SLIB_STS1 + sLib status 1 register + 0xD0 + 0x20 + 0xFFFFFFFF + + + SLIB_SS + sLib start sector + 0 + 16 + read-only + + + SLIB_ES + sLib end sector + 16 + 16 + read-only + + + + + SLIB_PWD_CLR + SLIB_PWD_CLR + SLIB password clear register + 0xD4 + 0x20 + 0x00000000 + write-only + + + SLIB_PCLR_VAL + sLib password clear value + 0 + 32 + + + + + SLIB_MISC_STS + SLIB_MISC_STS + sLib misc status register + 0xD8 + 0x20 + 0x01000000 + + + SLIB_PWD_ERR + sLib password error + 0 + 1 + read-only + + + SLIB_PWD_OK + sLib password ok + 1 + 1 + read-only + + + SLIB_ULKF + sLib unlock flag + 2 + 1 + read-only + + + SLIB_RCNT + sLib remaining count + 16 + 9 + read-only + + + + + SLIB_SET_PWD + SLIB_SET_PWD + sLib password setting register + 0xDC + 0x20 + 0x00000000 + write-only + + + SLIB_PSET_VAL + sLib password setting val + 0 + 32 + + + + + SLIB_SET_RANGE0 + SLIB_SET_RANGE0 + Configure sLib range register 0 + 0xE0 + 0x20 + 0x00000000 + write-only + + + SLIB_SS_SET + sLib start sector setting + 0 + 16 + + + SLIB_ES_SET + sLib end sector setting + 16 + 16 + + + + + SLIB_SET_RANGE1 + SLIB_SET_RANGE1 + Configure sLib range register 1 + 0xE4 + 0x20 + 0x00000000 + write-only + + + SLIB_ISS_SET + sLib instruction start sector setting + 0 + 16 + + + SET_SLIB_STRT + sLib start setting + 31 + 1 + + + + + SLIB_UNLOCK + SLIB_UNLOCK + sLib unlock register + 0xF0 + 0x20 + 0x00000000 + write-only + + + SLIB_UKVAL + sLib unlock key value + 0 + 32 + + + + + CRC_CTRL + CRC_CTRL + CRC controler register + 0xF4 + 0x20 + 0x00000000 + write-only + + + CRC_SS + CRC start sector + 0 + 12 + + + CRC_SN + CRC sector numbler + 12 + 12 + + + CRC_STRT + CRC start + 31 + 1 + + + + + CRC_CHKR + CRC_CHKR + CRC check result register + 0xF8 + 0x20 + 0x00000000 + read-only + + + CRC_CHKR + CRC check result + 0 + 32 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E000 + + 0x0 + 0x1001 + registers + + + + 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 + + + + + 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 + + + + + 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 + + + + + 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 + + + + + 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 + + + + + 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 + + + + + + + DVP + Digital video parallel interface + DVP + 0x50050000 + + 0x0 + 0x400 + registers + + + DVP + DVP global interrupt + 78 + + + + CTRL + CTRL + Control register + 0x0 + 0x20 + 0x0000 + + + LCDS + Line capture/drop selection + 20 + 1 + read-write + + + LCDC + Line capture/drop control + + 19 + 1 + read-write + + + PCDS + Pixel capture/drop selection + + 18 + 1 + read-write + + + PCDC + Basic pixel capture/drop control + + 16 + 2 + read-write + + + ENA + DVP enable + 14 + 1 + read-write + + + PDL + Pixel data length + 10 + 2 + read-write + + + BFRC + Basic frame rate control + 8 + 2 + read-write + + + VSP + Vertical synchronization + polarity + 7 + 1 + read-write + + + HSP + Horizontal synchronization polarity + + 6 + 1 + read-write + + + CKP + Pixel clock polarity + 5 + 1 + read-write + + + SM + synchronization mode + 4 + 1 + read-write + + + JPEG + JPEG format + 3 + 1 + read-write + + + CRP + Cropping function enable + 2 + 1 + read-write + + + CFM + Capture fire mode + 1 + 1 + read-write + + + CAP + Capture function enable + 0 + 1 + read-write + + + + + STS + STS + status register + 0x4 + 0x20 + read-only + 0x0000 + + + OFNE + Output FIFO Non-empty + 2 + 1 + + + VSYN + Vertical synchronization status + 1 + 1 + + + HSYN + Horizontal synchronization status + 0 + 1 + + + + + ESTS + ESTS + Event status register + 0x8 + 0x20 + read-only + 0x0000 + + + HSES + Horizontal synchronization event status + 4 + 1 + + + VSES + Vertical synchronization event status + 3 + 1 + + + ESEES + Embedded synchronization error event status + + 2 + 1 + + + OVRES + Data FIFO overrun event status + + 1 + 1 + + + CFDES + Capture frame done event status + + 0 + 1 + + + + + IENA + IENA + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + HSIE + Horizontal synchronization interrupt enable + + 4 + 1 + + + VSIE + Vertical synchronization interrupt enablee + + 3 + 1 + + + ESEIE + Embedded synchronization error interrupt + enable + 2 + 1 + + + OVRIE + Data FIFO overrun interrupt enable + + 1 + 1 + + + CFDIE + Capture frame done interrupt enable + + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-only + 0x0000 + + + HSIS + Horizontal synchronization interrupt + status + 4 + 1 + + + VSIS + Vertical synchronization interrupt + status + 3 + 1 + + + ESEIS + Embedded synchronization error + interrupt status + 2 + 1 + + + OVRIS + Data FIFO overrun interrupt + status + 1 + 1 + + + CFDIS + Capture frame done interrupt + status + 0 + 1 + + + + + ICLR + ICLR + Interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + HSIC + Horizontal synchronization + interrupt clear + 4 + 1 + + + VSIC + Vertical synchronization + interrupt clear + 3 + 1 + + + ESEIC + Embedded synchronization + error interrupt clear + 2 + 1 + + + OVRIC + Data FIFO overrun + interrupt clear + 1 + 1 + + + CFDIC + Capture frame done + interrupt clear + 0 + 1 + + + + + SCR + SCR + Synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FMEC + Frame end code + 24 + 8 + + + LNEC + Line end code + 16 + 8 + + + LNSC + Line start code + 8 + 8 + + + FMSC + Frame start code + 0 + 8 + + + + + SUR + SUR + Synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FMEU + Frame end unmask + 24 + 8 + + + LNEU + Line end unmask + 16 + 8 + + + LNSU + Line start unmask + + 8 + 8 + + + FMSU + Frame start unmask + + 0 + 8 + + + + + CWST + CWST + Crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + CVSTR + Cropping window vertical start line + + 16 + 13 + + + CHSTR + Cropping window horizontal start pixel + + 0 + 14 + + + + + CWSZ + CWSZ + Crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + CVNUM + Cropping window vertical line number + + 16 + 14 + + + CHNUM + Cropping window horizontal pixel number + + 0 + 14 + + + + + DT + DT + Data register + 0x28 + 0x20 + read-only + 0x0000 + + + DT + Data Port + 0 + 32 + + + + + ACTRL + ACTRL + Advanced Control register + + 0x40 + 0x20 + read-write + 0x0000 + + + VSEID + Vertical synchonization event and interrupt + definition + 17 + 1 + + + HSEID + Horizontal synchonization event and interrupt + definition + 16 + 1 + + + DMABT + DMA burst transfer configuration + + 12 + 1 + + + IDUS + Input data un-used setting + + 10 + 1 + + + IDUN + Input data un-used number + + 8 + 2 + + + EFDM + Enhanced function data format management + + 6 + 1 + + + EFDF + Enhanced function data format + + 4 + 2 + + + PCDES + Basic pixel capture/drop extended + selection + 3 + 1 + + + MIBE + Monochrome image binarization + enable + 2 + 1 + + + EFRCE + Enhanced frame rate control + enable + 1 + 1 + + + EISRE + Enhanced image scaling resize + enable + 0 + 1 + + + + + HSCF + HSCF + Horizontal scaling control flow + + 0x48 + 0x20 + read-write + 0x0000 + + + HSRTF + Horizontal scaling resize target factor + + 16 + 13 + + + HSRSF + Horizontal scaling resize source factor + + 0 + 13 + + + + + VSCF + VSCF + Vertical scaling control flow + + 0x4C + 0x20 + read-write + 0x0000 + + + VSRTF + Vertical scaling resize target factor + + 16 + 13 + + + VSRSF + Vertical scaling resize source factor + + 0 + 13 + + + + + FRF + FRF + Frame rate flow + + 0x50 + 0x20 + read-write + 0x0000 + + + EFRCTF + Enhanced frame rate control target factor + + 8 + 5 + + + EFRCSF + Enhanced frame rate contorl source factor + + 0 + 5 + + + + + BTH + BTH + Binarization threshold + + 0x54 + 0x20 + read-write + 0x0000 + + + MIBTHD + Monochrome image binarization threshold + + 0 + 8 + + + + + + + USB_OTG1_GLOBAL + USB on-the-go full speed + USB_OTG1 + 0x50000000 + + 0x0 + 0x400 + registers + + + OTGFS1 + USB On The Go FS global + interrupt + 67 + + + + GOTGCTL + GOTGCTL + OTGFS control and status register + (OTGFS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + CONIDSTS + Connector ID status + 16 + 1 + read-only + + + CURMOD + Current Mode of Operation + 21 + 1 + read-only + + + + + GOTGINT + GOTGINT + OTGFS interrupt register + (OTGFS_GOTGINT) + 0x4 + 0x20 + 0x00000000 + + + SESENDDET + VBUS is deasserted + 2 + 1 + read-write + + + + + GAHBCFG + GAHBCFG + OTGFS AHB configuration register + (OTGFS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GLBINTMSK + Global interrupt mask + 0 + 1 + + + NPTXFEMPLVL + Non-Periodic TxFIFO empty level + 7 + 1 + + + PTXFEMPLVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + GUSBCFG + GUSBCFG + USB configuration register + (OTGFS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOUTCAL + FS timeout calibration + 0 + 3 + read-write + + + USBTRDTIM + USB turnaround time + 10 + 4 + read-write + + + FHSTMODE + Force host mode + 29 + 1 + read-write + + + FDEVMODE + Force device mode + 30 + 1 + read-write + + + COTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + GRSTCTL + GRSTCTL + OTGFS reset register + (OTGFS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSFTRST + Core soft reset + 0 + 1 + read-write + + + PIUSFTRST + PIU FS Dedicated Controller Soft Reset + 1 + 1 + read-write + + + FRMCNTRST + 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 + + + AHBIDLE + AHB master idle + 31 + 1 + read-only + + + + + GINTSTS + GINTSTS + OTGFS core interrupt register + (OTGFS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CURMOD + Current mode of operation + 0 + 1 + read-only + + + MODEMIS + 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 + + + NPTXFEMP + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINNAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ERLYSUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDONE + Enumeration done + 13 + 1 + read-write + + + ISOOUTDROP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPTINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPTINT + OUT endpoint interrupt + 19 + 1 + read-only + + + INCOMPISOIN + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + PRTINT + Host port interrupt + 24 + 1 + read-only + + + HCHINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFEMP + Periodic TxFIFO empty + 26 + 1 + read-only + + + CONIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCONINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + GINTMSK + GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MODEMISMSK + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINTMSK + OTG interrupt mask + 2 + 1 + read-write + + + SOFMSK + Start of frame mask + 3 + 1 + read-write + + + RXFLVLMSK + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEMPMSK + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINNAKEFFMSK + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GOUTNAKEFFMSK + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ERLYSUSPMSK + Early suspend mask + 10 + 1 + read-write + + + USBSUSPMSK + USB suspend mask + 11 + 1 + read-write + + + USBRSTMSK + USB reset mask + 12 + 1 + read-write + + + ENUMDONEMSK + Enumeration done mask + 13 + 1 + read-write + + + ISOOUTDROPMSK + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFMSK + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPTINTMSK + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPTINTMSK + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + INCOMISOINMSK + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUTMSK + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTINTMSK + Host port interrupt mask + 24 + 1 + read-write + + + HCHINTMSK + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEMPMSK + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CONIDSCHGMSK + Connector ID status change + mask + 28 + 1 + read-write + + + DISCONINTMSK + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + WKUPINTMSK + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + GRXSTSR_Device + GRXSTSR_Device + OTGFS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPTNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FN + Frame number + 21 + 4 + + + + + GRXSTSR_Host + GRXSTSR_Host + OTGFS Receive status debug read(Host + mode) + GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + GRXFSIZ + GRXFSIZ + OTGFS Receive FIFO size register + (OTGFS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFDEP + RxFIFO depth + 0 + 16 + + + + + DIEPTXF0 + DIEPTXF0 + IN Endpoint TxFIFO 0 transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + INEPT0TXSTADDR + Endpoint 0 transmit RAM start + address + 0 + 16 + + + INEPT0TXDEP + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + GNPTXFSIZ + GNPTXFSIZ + OTGFS non-periodic transmit FIFO size + register (Host mode) + DIEPTXF0 + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSTADDR + Non-periodic Transmit RAM Start + address + 0 + 16 + + + NPTXFDEP + Non-periodic TxFIFO depth + 16 + 16 + + + + + GNPTXSTS + GNPTXSTS + OTGFS non-periodic transmit FIFO/queue + status register (OTGFS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSPCAVAIL + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTXQSPCAVAIL + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + GCCFG + GCCFG + OTGFS general core configuration register + (OTGFS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDOWN + Power down + 16 + 1 + + + LP_MODE + Low power mode + 17 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + VBUSIG + VBUS Ignored + 21 + 1 + + + + + GUID + GUID + Product ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + USERID + Product ID field + 0 + 32 + + + + + HPTXFSIZ + HPTXFSIZ + OTGFS Host periodic transmit FIFO size + register (OTGFS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXFSTADDR + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZE + Host periodic TxFIFO depth + 16 + 16 + + + + + DIEPTXF1 + DIEPTXF1 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO1 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF2 + DIEPTXF2 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF3 + DIEPTXF3 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF4 + DIEPTXF4 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF5 + DIEPTXF5 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO5 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF6 + DIEPTXF6 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF6) + 0x118 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO6 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF7 + DIEPTXF7 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF7) + 0x11C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO7 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + USB_OTG1_HOST + USB on the go full speed + USB_OTG1 + 0x50000400 + + 0x0 + 0x400 + registers + + + + HCFG + HCFG + OTGFS host configuration register + (OTGFS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCLKSEL + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSSUPP + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTGFS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRINT + Frame interval + 0 + 16 + + + + + HFNUM + HFNUM + OTGFS host frame number/frame time + remaining register (OTGFS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + HPTXSTS + HPTXSTS + OTGFS_Host periodic transmit FIFO/queue + status register (OTGFS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSPCAVAIL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSPCAVAIL + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTGFS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTGFS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTMSK + Channel interrupt mask + 0 + 16 + + + + + HPRT + HPRT + OTGFS host port control and status register + (OTGFS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PRTCONSTS + Port connect status + 0 + 1 + read-only + + + PRTCONDET + Port connect detected + 1 + 1 + read-write + + + PRTENA + Port enable + 2 + 1 + read-write + + + PRTENCHNG + Port enable/disable change + 3 + 1 + read-write + + + PRTOVRCACT + Port overcurrent active + 4 + 1 + read-only + + + PRTOVRCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRTRES + Port resume + 6 + 1 + read-write + + + PRTSUSP + Port suspend + 7 + 1 + read-write + + + PRTRST + Port reset + 8 + 1 + read-write + + + PRTLNSTS + Port line status + 10 + 2 + read-only + + + PRTPWR + Port power + 12 + 1 + read-write + + + PRTTSTCTL + Port test control + 13 + 4 + read-write + + + PRTSPD + Port speed + 17 + 2 + read-only + + + + + HCCHAR0 + HCCHAR0 + OTGFS host channel-0 characteristics + register (OTGFS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR1 + HCCHAR1 + OTGFS host channel-1 characteristics + register (OTGFS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR2 + HCCHAR2 + OTGFS host channel-2 characteristics + register (OTGFS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR3 + HCCHAR3 + OTGFS host channel-3 characteristics + register (OTGFS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR4 + HCCHAR4 + OTGFS host channel-4 characteristics + register (OTGFS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR5 + HCCHAR5 + OTGFS host channel-5 characteristics + register (OTGFS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR6 + HCCHAR6 + OTGFS host channel-6 characteristics + register (OTGFS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR7 + HCCHAR7 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR8 + HCCHAR8 + OTGFS host channel-8 characteristics + register (OTGFS_HCCHAR8) + 0x200 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR9 + HCCHAR9 + OTGFS host channel-9 characteristics + register (OTGFS_HCCHAR9) + 0x220 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR10 + HCCHAR10 + OTGFS host channel-10 characteristics + register (OTGFS_HCCHAR10) + 0x240 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR11 + HCCHAR11 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR11) + 0x260 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR12 + HCCHAR12 + OTGFS host channel-12 characteristics + register (OTGFS_HCCHAR12) + 0x280 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR13 + HCCHAR13 + OTGFS host channel-13 characteristics + register (OTGFS_HCCHAR13) + 0x2A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR14 + HCCHAR14 + OTGFS host channel-14 characteristics + register (OTGFS_HCCHAR14) + 0x2C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR15 + HCCHAR15 + OTGFS host channel-15 characteristics + register (OTGFS_HCCHAR15) + 0x2E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCINT0 + HCINT0 + OTGFS host channel-0 interrupt register + (OTGFS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT1 + HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT2 + HCINT2 + OTGFS host channel-2 interrupt register + (OTGFS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT3 + HCINT3 + OTGFS host channel-3 interrupt register + (OTGFS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT4 + HCINT4 + OTGFS host channel-4 interrupt register + (OTGFS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT5 + HCINT5 + OTGFS host channel-5 interrupt register + (OTGFS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT6 + HCINT6 + OTGFS host channel-6 interrupt register + (OTGFS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT7 + HCINT7 + OTGFS host channel-7 interrupt register + (OTGFS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT8 + HCINT8 + OTGFS host channel-8 interrupt register + (OTGFS_HCINT8) + 0x208 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT9 + HCINT9 + OTGFS host channel-9 interrupt register + (OTGFS_HCINT9) + 0x228 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT10 + HCINT10 + OTGFS host channel-10 interrupt register + (OTGFS_HCINT10) + 0x248 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT11 + HCINT11 + OTGFS host channel-11 interrupt register + (OTGFS_HCINT11) + 0x268 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT12 + HCINT12 + OTGFS host channel-12 interrupt register + (OTGFS_HCINT12) + 0x288 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT13 + HCINT13 + OTGFS host channel-13 interrupt register + (OTGFS_HCINT13) + 0x2A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT14 + HCINT14 + OTGFS host channel-14 interrupt register + (OTGFS_HCINT14) + 0x2C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT15 + HCINT15 + OTGFS host channel-15 interrupt register + (OTGFS_HCINT15) + 0x2E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINTMSK0 + HCINTMSK0 + OTGFS host channel-0 mask register + (OTGFS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK1 + HCINTMSK1 + OTGFS host channel-1 mask register + (OTGFS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK2 + HCINTMSK2 + OTGFS host channel-2 mask register + (OTGFS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK3 + HCINTMSK3 + OTGFS host channel-3 mask register + (OTGFS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK4 + HCINTMSK4 + OTGFS host channel-4 mask register + (OTGFS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK5 + HCINTMSK5 + OTGFS host channel-5 mask register + (OTGFS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK6 + HCINTMSK6 + OTGFS host channel-6 mask register + (OTGFS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK7 + HCINTMSK7 + OTGFS host channel-7 mask register + (OTGFS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK8 + HCINTMSK8 + OTGFS host channel-8 mask register + (OTGFS_HCINTMSK8) + 0x20C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK9 + HCINTMSK9 + OTGFS host channel-9 mask register + (OTGFS_HCINTMSK9) + 0x22C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK10 + HCINTMSK10 + OTGFS host channel-10 mask register + (OTGFS_HCINTMSK10) + 0x24C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK11 + HCINTMSK11 + OTGFS host channel-11 mask register + (OTGFS_HCINTMSK11) + 0x26C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK12 + HCINTMSK12 + OTGFS host channel-12 mask register + (OTGFS_HCINTMSK12) + 0x28C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK13 + HCINTMSK13 + OTGFS host channel-13 mask register + (OTGFS_HCINTMSK13) + 0x2AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK14 + HCINTMSK14 + OTGFS host channel-14 mask register + (OTGFS_HCINTMSK14) + 0x2CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK15 + HCINTMSK15 + OTGFS host channel-15 mask register + (OTGFS_HCINTMSK15) + 0x2EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCTSIZ0 + HCTSIZ0 + OTGFS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ1 + HCTSIZ1 + OTGFS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ2 + HCTSIZ2 + OTGFS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ3 + HCTSIZ3 + OTGFS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ4 + HCTSIZ4 + OTGFS host channel-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ5 + HCTSIZ5 + OTGFS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ6 + HCTSIZ6 + OTGFS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ7 + HCTSIZ7 + OTGFS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ8 + HCTSIZ8 + OTGFS host channel-8 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ9 + HCTSIZ9 + OTGFS host channel-9 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ10 + HCTSIZ10 + OTGFS host channel-10 transfer size + register + 0x250 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ11 + HCTSIZ11 + OTGFS host channel-11 transfer size + register + 0x270 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ12 + HCTSIZ12 + OTGFS host channel-12 transfer size + register + 0x290 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ13 + HCTSIZ13 + OTGFS host channel-13 transfer size + register + 0x2B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ14 + HCTSIZ14 + OTGFS host channel-14 transfer size + register + 0x2D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ15 + HCTSIZ15 + OTGFS host channel-15 transfer size + register + 0x2F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + + + USB_OTG1_DEVICE + USB on the go full speed + USB_OTG1 + 0x50000800 + + 0x0 + 0x400 + registers + + + + DCFG + DCFG + OTGFS device configuration register + (OTGFS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DEVSPD + Device speed + 0 + 2 + + + NZSTSOUTHSHK + Non-zero-length status OUT + handshake + 2 + 1 + + + DEVADDR + Device address + 4 + 7 + + + PERFRINT + Periodic frame interval + 11 + 2 + + + + + DCTL + DCTL + OTGFS device control register + (OTGFS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWKUPSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SFTDISCON + Soft disconnect + 1 + 1 + read-write + + + GNPINNAKSTS + Global IN NAK status + 2 + 1 + read-only + + + GOUTNAKSTS + Global OUT NAK status + 3 + 1 + read-only + + + TSTCTL + Test control + 4 + 3 + read-write + + + SGNPINNAK + Set global IN NAK + 7 + 1 + read-write + + + CGNPINNAK + Clear global IN NAK + 8 + 1 + read-write + + + SGOUTNAK + Set global OUT NAK + 9 + 1 + read-write + + + CGOUTNAK + Clear global OUT NAK + 10 + 1 + read-write + + + PWROPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + DSTS + DSTS + OTGFS device status register + (OTGFS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + ETICERR + Erratic error + 3 + 1 + + + SOFFN + Frame number of the received + SOF + 8 + 14 + + + + + DIEPMSK + DIEPMSK + OTGFS device IN endpoint common interrupt + mask register (OTGFS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + TIMEOUTMSK + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + INTKNTXFEMPMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INTKNEPTMISMSK + IN token received with EP mismatch + mask + 5 + 1 + + + INEPTNAKMSK + IN endpoint NAK effective + mask + 6 + 1 + + + TXFIFOUDRMSK + FIFO underrun + mask + 8 + 1 + + + BNAINMSK + BNA interrupt + mask + 9 + 1 + + + + + DOEPMSK + DOEPMSK + OTGFS device OUT endpoint common interrupt + mask register (OTGFS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + SETUPMSK + SETUP phase done mask + 3 + 1 + + + OUTTEPDMSK + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSETUPMSK + Back-to-back SETUP packets + received mask + 6 + 1 + + + OUTPERRMSK + OUT packet error + mask + 8 + 1 + + + BNAOUTMSK + BNA interrupt + mask + 9 + 1 + + + + + DAINT + DAINT + OTGFS device all endpoints interrupt + register (OTGFS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + INEPTINT + IN endpoint interrupt bits + 0 + 16 + + + OUTEPTINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DAINTMSK + DAINTMSK + OTGFS all endpoints interrupt mask register + (OTGFS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + INEPTMSK + IN EP interrupt mask bits + 0 + 16 + + + OUTEPTMSK + OUT endpoint interrupt + bits + 16 + 16 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTGFS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEMSK + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + DIEPCTL0 + DIEPCTL0 + OTGFS device control IN endpoint 0 control + register (OTGFS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 2 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-only + + + EPTENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTGFS device IN endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTGFS device IN endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTGFS device IN endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL4 + DIEPCTL4 + OTGFS device IN endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL5 + DIEPCTL5 + OTGFS device IN endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL6 + DIEPCTL6 + OTGFS device IN endpoint-6 control + register + 0x1C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL7 + DIEPCTL7 + OTGFS device IN endpoint-7 control + register + 0x1E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + OTGFS device OUT endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + MPS + Maximum packet size + 0 + 2 + read-only + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL1 + DOEPCTL1 + OTGFS device OUT endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + OTGFS device OUT endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + OTGFS device OUT endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL4 + DOEPCTL4 + OTGFS device OUT endpoint-4 control + register + 0x380 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL5 + DOEPCTL5 + OTGFS device OUT endpoint-5 control + register + 0x3A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL6 + DOEPCTL6 + OTGFS device OUT endpoint-6 control + register + 0x3C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL7 + DOEPCTL7 + OTGFS device OUT endpoint-7 control + register + 0x3E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPINT0 + DIEPINT0 + OTGFS device IN endpoint-0 interrupt + register + 0x108 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT1 + DIEPINT1 + OTGFS device IN endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT2 + DIEPINT2 + OTGFS device IN endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT3 + DIEPINT3 + OTGFS device IN endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT4 + DIEPINT4 + OTGFS device IN endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT5 + DIEPINT5 + OTGFS device IN endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT6 + DIEPINT6 + OTGFS device IN endpoint-6 interrupt + register + 0x1C8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT7 + DIEPINT7 + OTGFS device IN endpoint-7 interrupt + register + 0x1E8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DOEPINT0 + DOEPINT0 + OTGFS device OUT endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT1 + DOEPINT1 + OTGFS device OUT endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT2 + DOEPINT2 + OTGFS device OUT endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT3 + DOEPINT3 + OTGFS device OUT endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT4 + DOEPINT4 + OTGFS device OUT endpoint-4 interrupt + register + 0x388 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT5 + DOEPINT5 + OTGFS device OUT endpoint-5 interrupt + register + 0x3A8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT6 + DOEPINT6 + OTGFS device OUT endpoint-6 interrupt + register + 0x3C8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT7 + DOEPINT7 + OTGFS device OUT endpoint-7 interrupt + register + 0x3E8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + OTGFS device IN endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + OTGFS device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + SETUPCNT + SETUP packet count + 29 + 2 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + OTGFS device IN endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + OTGFS device IN endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + OTG device IN endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ4 + DIEPTSIZ4 + OTG device IN endpoint-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ5 + DIEPTSIZ5 + OTG device IN endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ6 + DIEPTSIZ6 + OTG device IN endpoint-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ7 + DIEPTSIZ7 + OTG device IN endpoint-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DTXFSTS0 + DTXFSTS0 + OTGFS device IN endpoint-0 transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTGFS device IN endpoint-1 transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTGFS device IN endpoint-2 transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTGFS device IN endpoint-3 transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS4 + DTXFSTS4 + OTGFS device IN endpoint-4 transmit FIFO + status register + 0x198 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS5 + DTXFSTS5 + OTGFS device IN endpoint-5 transmit FIFO + status register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS6 + DTXFSTS6 + OTGFS device IN endpoint-6 transmit FIFO + status register + 0x1D8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS7 + DTXFSTS7 + OTGFS device IN endpoint-7 transmit FIFO + status register + 0x1F8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + OTGFS device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + OTGFS device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + OTGFS device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ4 + DOEPTSIZ4 + OTGFS device OUT endpoint-4 transfer size + register + 0x390 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ5 + DOEPTSIZ5 + OTGFS device OUT endpoint-5 transfer size + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ6 + DOEPTSIZ6 + OTGFS device OUT endpoint-6 transfer size + register + 0x3D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ7 + DOEPTSIZ7 + OTGFS device OUT endpoint-7 transfer size + register + 0x3F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + + + USB_OTG1_PWRCLK + USB on the go full speed + USB_OTG1 + 0x50000E00 + + 0x0 + 0x400 + registers + + + + PCGCCTL + PCGCCTL + OTGFS power and clock gating control + register (OTGFS_PCGCCTL) + 0x0 + 0x20 + 0x00000000 + + + STOPPCLK + Stop PHY clock + 0 + 1 + read-write + + + SUSPENDM + PHY Suspended + 4 + 1 + read-only + + + + + + + USB_OTG2_GLOBAL + USB on the go full speed + USB_OTG2 + 0x40040000 + + 0x0 + 0x400 + registers + + + OTGFS2 + USB On The Go FS2 global + interrupt + 77 + + + + GOTGCTL + GOTGCTL + OTGFS control and status register + (OTGFS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + CONIDSTS + Connector ID status + 16 + 1 + read-only + + + CURMOD + Current Mode of Operation + 21 + 1 + read-only + + + + + GOTGINT + GOTGINT + OTGFS interrupt register + (OTGFS_GOTGINT) + 0x4 + 0x20 + 0x00000000 + + + SESENDDET + VBUS is deasserted + 2 + 1 + read-write + + + + + GAHBCFG + GAHBCFG + OTGFS AHB configuration register + (OTGFS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GLBINTMSK + Global interrupt mask + 0 + 1 + + + NPTXFEMPLVL + Non-Periodic TxFIFO empty level + 7 + 1 + + + PTXFEMPLVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + GUSBCFG + GUSBCFG + USB configuration register + (OTGFS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOUTCAL + FS timeout calibration + 0 + 3 + read-write + + + USBTRDTIM + USB turnaround time + 10 + 4 + read-write + + + FHSTMODE + Force host mode + 29 + 1 + read-write + + + FDEVMODE + Force device mode + 30 + 1 + read-write + + + COTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + GRSTCTL + GRSTCTL + OTGFS reset register + (OTGFS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSFTRST + Core soft reset + 0 + 1 + read-write + + + PIUSFTRST + PIU FS Dedicated Controller Soft Reset + 1 + 1 + read-write + + + FRMCNTRST + 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 + + + AHBIDLE + AHB master idle + 31 + 1 + read-only + + + + + GINTSTS + GINTSTS + OTGFS core interrupt register + (OTGFS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CURMOD + Current mode of operation + 0 + 1 + read-only + + + MODEMIS + 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 + + + NPTXFEMP + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINNAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ERLYSUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDONE + Enumeration done + 13 + 1 + read-write + + + ISOOUTDROP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPTINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPTINT + OUT endpoint interrupt + 19 + 1 + read-only + + + INCOMPISOIN + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + PRTINT + Host port interrupt + 24 + 1 + read-only + + + HCHINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFEMP + Periodic TxFIFO empty + 26 + 1 + read-only + + + CONIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCONINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + GINTMSK + GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MODEMISMSK + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINTMSK + OTG interrupt mask + 2 + 1 + read-write + + + SOFMSK + Start of frame mask + 3 + 1 + read-write + + + RXFLVLMSK + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEMPMSK + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINNAKEFFMSK + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GOUTNAKEFFMSK + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ERLYSUSPMSK + Early suspend mask + 10 + 1 + read-write + + + USBSUSPMSK + USB suspend mask + 11 + 1 + read-write + + + USBRSTMSK + USB reset mask + 12 + 1 + read-write + + + ENUMDONEMSK + Enumeration done mask + 13 + 1 + read-write + + + ISOOUTDROPMSK + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFMSK + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPTINTMSK + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPTINTMSK + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + INCOMISOINMSK + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUTMSK + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTINTMSK + Host port interrupt mask + 24 + 1 + read-only + + + HCHINTMSK + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEMPMSK + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CONIDSCHGMSK + Connector ID status change + mask + 28 + 1 + read-write + + + DISCONINTMSK + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + WKUPINTMSK + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + GRXSTSR_Device + GRXSTSR_Device + OTGFS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPTNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FN + Frame number + 21 + 4 + + + + + GRXSTSR_Host + GRXSTSR_Host + OTGFS Receive status debug read(Host + mode) + GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + GRXFSIZ + GRXFSIZ + OTGFS Receive FIFO size register + (OTGFS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFDEP + RxFIFO depth + 0 + 16 + + + + + DIEPTXF0 + DIEPTXF0 + IN Endpoint TxFIFO 0 transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + INEPT0TXSTADDR + Endpoint 0 transmit RAM start + address + 0 + 16 + + + INEPT0TXDEP + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + GNPTXFSIZ + GNPTXFSIZ + OTGFS non-periodic transmit FIFO size + register (Host mode) + DIEPTXF0 + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSTADDR + Non-periodic Transmit RAM Start + address + 0 + 16 + + + NPTXFDEP + Non-periodic TxFIFO depth + 16 + 16 + + + + + GNPTXSTS + GNPTXSTS + OTGFS non-periodic transmit FIFO/queue + status register (OTGFS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSPCAVAIL + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTXQSPCAVAIL + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + GCCFG + GCCFG + OTGFS general core configuration register + (OTGFS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDOWN + Power down + 16 + 1 + + + LP_MODE + Low power mode + 17 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + VBUSIG + VBUS Ignored + 21 + 1 + + + + + GUID + GUID + Product ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + USERID + Product ID field + 0 + 32 + + + + + HPTXFSIZ + HPTXFSIZ + OTGFS Host periodic transmit FIFO size + register (OTGFS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXFSTADDR + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZE + Host periodic TxFIFO depth + 16 + 16 + + + + + DIEPTXF1 + DIEPTXF1 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO1 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF2 + DIEPTXF2 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF3 + DIEPTXF3 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF4 + DIEPTXF4 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF5 + DIEPTXF5 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO5 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF6 + DIEPTXF6 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF6) + 0x118 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO6 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF7 + DIEPTXF7 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF7) + 0x11C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO7 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + USB_OTG2_HOST + USB on the go full speed + USB_OTG2 + 0x40040400 + + 0x0 + 0x400 + registers + + + + HCFG + HCFG + OTGFS host configuration register + (OTGFS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCLKSEL + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSSUPP + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTGFS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRINT + Frame interval + 0 + 16 + + + + + HFNUM + HFNUM + OTGFS host frame number/frame time + remaining register (OTGFS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + HPTXSTS + HPTXSTS + OTGFS_Host periodic transmit FIFO/queue + status register (OTGFS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSPCAVAIL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSPCAVAIL + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTGFS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTGFS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTMSK + Channel interrupt mask + 0 + 16 + + + + + HPRT + HPRT + OTGFS host port control and status register + (OTGFS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PRTCONSTS + Port connect status + 0 + 1 + read-only + + + PRTCONDET + Port connect detected + 1 + 1 + read-write + + + PRTENA + Port enable + 2 + 1 + read-write + + + PRTENCHNG + Port enable/disable change + 3 + 1 + read-write + + + PRTOVRCACT + Port overcurrent active + 4 + 1 + read-only + + + PRTOVRCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRTRES + Port resume + 6 + 1 + read-write + + + PRTSUSP + Port suspend + 7 + 1 + read-write + + + PRTRST + Port reset + 8 + 1 + read-write + + + PRTLNSTS + Port line status + 10 + 2 + read-only + + + PRTPWR + Port power + 12 + 1 + read-write + + + PRTTSTCTL + Port test control + 13 + 4 + read-write + + + PRTSPD + Port speed + 17 + 2 + read-only + + + + + HCCHAR0 + HCCHAR0 + OTGFS host channel-0 characteristics + register (OTGFS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR1 + HCCHAR1 + OTGFS host channel-1 characteristics + register (OTGFS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR2 + HCCHAR2 + OTGFS host channel-2 characteristics + register (OTGFS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR3 + HCCHAR3 + OTGFS host channel-3 characteristics + register (OTGFS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR4 + HCCHAR4 + OTGFS host channel-4 characteristics + register (OTGFS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR5 + HCCHAR5 + OTGFS host channel-5 characteristics + register (OTGFS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR6 + HCCHAR6 + OTGFS host channel-6 characteristics + register (OTGFS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR7 + HCCHAR7 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR8 + HCCHAR8 + OTGFS host channel-8 characteristics + register (OTGFS_HCCHAR8) + 0x200 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR9 + HCCHAR9 + OTGFS host channel-9 characteristics + register (OTGFS_HCCHAR9) + 0x220 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR10 + HCCHAR10 + OTGFS host channel-10 characteristics + register (OTGFS_HCCHAR10) + 0x240 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR11 + HCCHAR11 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR11) + 0x260 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR12 + HCCHAR12 + OTGFS host channel-12 characteristics + register (OTGFS_HCCHAR12) + 0x280 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR13 + HCCHAR13 + OTGFS host channel-13 characteristics + register (OTGFS_HCCHAR13) + 0x2A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR14 + HCCHAR14 + OTGFS host channel-14 characteristics + register (OTGFS_HCCHAR14) + 0x2C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR15 + HCCHAR15 + OTGFS host channel-15 characteristics + register (OTGFS_HCCHAR15) + 0x2E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCINT0 + HCINT0 + OTGFS host channel-0 interrupt register + (OTGFS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT1 + HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT2 + HCINT2 + OTGFS host channel-2 interrupt register + (OTGFS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT3 + HCINT3 + OTGFS host channel-3 interrupt register + (OTGFS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT4 + HCINT4 + OTGFS host channel-4 interrupt register + (OTGFS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT5 + HCINT5 + OTGFS host channel-5 interrupt register + (OTGFS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT6 + HCINT6 + OTGFS host channel-6 interrupt register + (OTGFS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT7 + HCINT7 + OTGFS host channel-7 interrupt register + (OTGFS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT8 + HCINT8 + OTGFS host channel-8 interrupt register + (OTGFS_HCINT8) + 0x208 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT9 + HCINT9 + OTGFS host channel-9 interrupt register + (OTGFS_HCINT9) + 0x228 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT10 + HCINT10 + OTGFS host channel-10 interrupt register + (OTGFS_HCINT10) + 0x248 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT11 + HCINT11 + OTGFS host channel-11 interrupt register + (OTGFS_HCINT11) + 0x268 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT12 + HCINT12 + OTGFS host channel-12 interrupt register + (OTGFS_HCINT12) + 0x288 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT13 + HCINT13 + OTGFS host channel-13 interrupt register + (OTGFS_HCINT13) + 0x2A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT14 + HCINT14 + OTGFS host channel-14 interrupt register + (OTGFS_HCINT14) + 0x2C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT15 + HCINT15 + OTGFS host channel-15 interrupt register + (OTGFS_HCINT15) + 0x2E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + 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 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINTMSK0 + HCINTMSK0 + OTGFS host channel-0 mask register + (OTGFS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK1 + HCINTMSK1 + OTGFS host channel-1 mask register + (OTGFS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK2 + HCINTMSK2 + OTGFS host channel-2 mask register + (OTGFS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK3 + HCINTMSK3 + OTGFS host channel-3 mask register + (OTGFS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK4 + HCINTMSK4 + OTGFS host channel-4 mask register + (OTGFS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK5 + HCINTMSK5 + OTGFS host channel-5 mask register + (OTGFS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK6 + HCINTMSK6 + OTGFS host channel-6 mask register + (OTGFS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK7 + HCINTMSK7 + OTGFS host channel-7 mask register + (OTGFS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK8 + HCINTMSK8 + OTGFS host channel-8 mask register + (OTGFS_HCINTMSK8) + 0x20C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK9 + HCINTMSK9 + OTGFS host channel-9 mask register + (OTGFS_HCINTMSK9) + 0x22C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK10 + HCINTMSK10 + OTGFS host channel-10 mask register + (OTGFS_HCINTMSK10) + 0x24C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK11 + HCINTMSK11 + OTGFS host channel-11 mask register + (OTGFS_HCINTMSK11) + 0x26C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK12 + HCINTMSK12 + OTGFS host channel-12 mask register + (OTGFS_HCINTMSK12) + 0x28C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK13 + HCINTMSK13 + OTGFS host channel-13 mask register + (OTGFS_HCINTMSK13) + 0x2AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK14 + HCINTMSK14 + OTGFS host channel-14 mask register + (OTGFS_HCINTMSK14) + 0x2CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK15 + HCINTMSK15 + OTGFS host channel-15 mask register + (OTGFS_HCINTMSK15) + 0x2EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCTSIZ0 + HCTSIZ0 + OTGFS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ1 + HCTSIZ1 + OTGFS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ2 + HCTSIZ2 + OTGFS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ3 + HCTSIZ3 + OTGFS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ4 + HCTSIZ4 + OTGFS host channel-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ5 + HCTSIZ5 + OTGFS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ6 + HCTSIZ6 + OTGFS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ7 + HCTSIZ7 + OTGFS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ8 + HCTSIZ8 + OTGFS host channel-8 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ9 + HCTSIZ9 + OTGFS host channel-9 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ10 + HCTSIZ10 + OTGFS host channel-10 transfer size + register + 0x250 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ11 + HCTSIZ11 + OTGFS host channel-11 transfer size + register + 0x270 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ12 + HCTSIZ12 + OTGFS host channel-12 transfer size + register + 0x290 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ13 + HCTSIZ13 + OTGFS host channel-13 transfer size + register + 0x2B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ14 + HCTSIZ14 + OTGFS host channel-14 transfer size + register + 0x2D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ15 + HCTSIZ15 + OTGFS host channel-15 transfer size + register + 0x2F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + + + USB_OTG2_DEVICE + USB on the go full speed + USB_OTG2 + 0x40040800 + + 0x0 + 0x400 + registers + + + + DCFG + DCFG + OTGFS device configuration register + (OTGFS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DEVSPD + Device speed + 0 + 2 + + + NZSTSOUTHSHK + Non-zero-length status OUT + handshake + 2 + 1 + + + DEVADDR + Device address + 4 + 7 + + + PERFRINT + Periodic frame interval + 11 + 2 + + + + + DCTL + DCTL + OTGFS device control register + (OTGFS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWKUPSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SFTDISCON + Soft disconnect + 1 + 1 + read-write + + + GNPINNAKSTS + Global IN NAK status + 2 + 1 + read-only + + + GOUTNAKSTS + Global OUT NAK status + 3 + 1 + read-only + + + TSTCTL + Test control + 4 + 3 + read-write + + + SGNPINNAK + Set global IN NAK + 7 + 1 + read-write + + + CGNPINNAK + Clear global IN NAK + 8 + 1 + read-write + + + SGOUTNAK + Set global OUT NAK + 9 + 1 + read-write + + + CGOUTNAK + Clear global OUT NAK + 10 + 1 + read-write + + + PWROPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + DSTS + DSTS + OTGFS device status register + (OTGFS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + ETICERR + Erratic error + 3 + 1 + + + SOFFN + Frame number of the received + SOF + 8 + 14 + + + + + DIEPMSK + DIEPMSK + OTGFS device IN endpoint common interrupt + mask register (OTGFS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + TIMEOUTMSK + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + INTKNTXFEMPMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INTKNEPTMISMSK + IN token received with EP mismatch + mask + 5 + 1 + + + INEPTNAKMSK + IN endpoint NAK effective + mask + 6 + 1 + + + TXFIFOUDRMSK + FIFO underrun + mask + 8 + 1 + + + BNAINMSK + BNA interrupt + mask + 9 + 1 + + + + + DOEPMSK + DOEPMSK + OTGFS device OUT endpoint common interrupt + mask register (OTGFS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + SETUPMSK + SETUP phase done mask + 3 + 1 + + + OUTTEPDMSK + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSETUPMSK + Back-to-back SETUP packets + received mask + 6 + 1 + + + OUTPERRMSK + OUT packet error + mask + 8 + 1 + + + BNAOUTMSK + BNA interrupt + mask + 9 + 1 + + + + + DAINT + DAINT + OTGFS device all endpoints interrupt + register (OTGFS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + INEPTINT + IN endpoint interrupt bits + 0 + 16 + + + OUTEPTINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DAINTMSK + DAINTMSK + OTGFS all endpoints interrupt mask register + (OTGFS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + INEPTMSK + IN EP interrupt mask bits + 0 + 16 + + + OUTEPTMSK + OUT endpoint interrupt + bits + 16 + 16 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTGFS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEMSK + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + DIEPCTL0 + DIEPCTL0 + OTGFS device control IN endpoint 0 control + register (OTGFS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 2 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-only + + + EPTENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTGFS device IN endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTGFS device IN endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTGFS device IN endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL4 + DIEPCTL4 + OTGFS device IN endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL5 + DIEPCTL5 + OTGFS device IN endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL6 + DIEPCTL6 + OTGFS device IN endpoint-6 control + register + 0x1C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL7 + DIEPCTL7 + OTGFS device IN endpoint-7 control + register + 0x1E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + 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 + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + OTGFS device OUT endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + MPS + Maximum packet size + 0 + 2 + read-only + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL1 + DOEPCTL1 + OTGFS device OUT endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + OTGFS device OUT endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + OTGFS device OUT endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL4 + DOEPCTL4 + OTGFS device OUT endpoint-4 control + register + 0x380 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL5 + DOEPCTL5 + OTGFS device OUT endpoint-5 control + register + 0x3A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL6 + DOEPCTL6 + OTGFS device OUT endpoint-6 control + register + 0x3C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL7 + DOEPCTL7 + OTGFS device OUT endpoint-7 control + register + 0x3E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + 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 + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPINT0 + DIEPINT0 + OTGFS device IN endpoint-0 interrupt + register + 0x108 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT1 + DIEPINT1 + OTGFS device IN endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT2 + DIEPINT2 + OTGFS device IN endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT3 + DIEPINT3 + OTGFS device IN endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT4 + DIEPINT4 + OTGFS device IN endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT5 + DIEPINT5 + OTGFS device IN endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT6 + DIEPINT6 + OTGFS device IN endpoint-6 interrupt + register + 0x1C8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT7 + DIEPINT7 + OTGFS device IN endpoint-7 interrupt + register + 0x1E8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DOEPINT0 + DOEPINT0 + OTGFS device OUT endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT1 + DOEPINT1 + OTGFS device OUT endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT2 + DOEPINT2 + OTGFS device OUT endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT3 + DOEPINT3 + OTGFS device OUT endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT4 + DOEPINT4 + OTGFS device OUT endpoint-4 interrupt + register + 0x388 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT5 + DOEPINT5 + OTGFS device OUT endpoint-5 interrupt + register + 0x3A8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT6 + DOEPINT6 + OTGFS device OUT endpoint-6 interrupt + register + 0x3C8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT7 + DOEPINT7 + OTGFS device OUT endpoint-7 interrupt + register + 0x3E8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + OTGFS device IN endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + OTGFS device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + SETUPCNT + SETUP packet count + 29 + 2 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + OTGFS device IN endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + OTGFS device IN endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + OTG device IN endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ4 + DIEPTSIZ4 + OTG device IN endpoint-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ5 + DIEPTSIZ5 + OTG device IN endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ6 + DIEPTSIZ6 + OTG device IN endpoint-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ7 + DIEPTSIZ7 + OTG device IN endpoint-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DTXFSTS0 + DTXFSTS0 + OTGFS device IN endpoint-0 transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTGFS device IN endpoint-1 transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTGFS device IN endpoint-2 transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTGFS device IN endpoint-3 transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS4 + DTXFSTS4 + OTGFS device IN endpoint-4 transmit FIFO + status register + 0x198 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS5 + DTXFSTS5 + OTGFS device IN endpoint-5 transmit FIFO + status register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS6 + DTXFSTS6 + OTGFS device IN endpoint-6 transmit FIFO + status register + 0x1D8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS7 + DTXFSTS7 + OTGFS device IN endpoint-7 transmit FIFO + status register + 0x1F8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + OTGFS device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + OTGFS device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + OTGFS device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ4 + DOEPTSIZ4 + OTGFS device OUT endpoint-4 transfer size + register + 0x390 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ5 + DOEPTSIZ5 + OTGFS device OUT endpoint-5 transfer size + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ6 + DOEPTSIZ6 + OTGFS device OUT endpoint-6 transfer size + register + 0x3D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ7 + DOEPTSIZ7 + OTGFS device OUT endpoint-7 transfer size + register + 0x3F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + + + USB_OTG2_PWRCLK + USB on the go full speed + USB_OTG2 + 0x40040E00 + + 0x0 + 0x400 + registers + + + + PCGCCTL + PCGCCTL + OTGFS power and clock gating control + register (OTGFS_PCGCCTL) + 0x0 + 0x20 + 0x00000000 + + + STOPPCLK + Stop PHY clock + 0 + 1 + read-write + + + SUSPENDM + PHY Suspended + 4 + 1 + read-only + + + + + + + SCFG + System configuration controller + SCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + CFG1 + CFG1 + configuration register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MAP_SEL + Memory address mapping selection bits + 0 + 3 + + + IR_POL + IR output polarity selection + 5 + 1 + + + IR_SRC_SEL + IR signal source selection + 6 + 2 + + + SWAP_XMC + XMC address mapping swap + 10 + 2 + + + + + CFG2 + CFG2 + configuration register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + MII or RMII selection + bits + 23 + 1 + + + + + EXINTC1 + EXINTC1 + external interrupt configuration register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXINT3 + EXINT 3 configuration bits + 12 + 4 + + + EXINT2 + EXINT 2 configuration bits + 8 + 4 + + + EXINT1 + EXINT 1 configuration bits + 4 + 4 + + + EXINT0 + EXINT 0 configuration bits + 0 + 4 + + + + + EXINTC2 + EXINTC2 + external interrupt configuration register 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXINT7 + EXINT 7 configuration bits + 12 + 4 + + + EXINT6 + EXINT 6 configuration bits + 8 + 4 + + + EXINT5 + EXINT 5 configuration bits + 4 + 4 + + + EXINT4 + EXINT 4 configuration bits + 0 + 4 + + + + + EXINTC3 + EXINTC3 + external interrupt configuration register 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXINT11 + EXINT 11 configuration bits + 12 + 4 + + + EXINT10 + EXINT 10 configuration bits + 8 + 4 + + + EXINT9 + EXINT 9 configuration bits + 4 + 4 + + + EXINT8 + EXINT 8 configuration bits + 0 + 4 + + + + + EXINTC4 + EXINTC4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXINT15 + EXINT 15 configuration bits + 12 + 4 + + + EXINT14 + EXINT 14 configuration bits + 8 + 4 + + + EXINT13 + EXINT 13 configuration bits + 4 + 4 + + + EXINT12 + EXINT 12 configuration bits + 0 + 4 + + + + + UHDRV + UHDRV + Ultra high drive register + 0x2C + 0x20 + read-write + 0x0000 + + + PF15_UH + PF15 ultra high sourcing/sinking strength + 10 + 1 + + + PF14_UH + PF14 ultra high sourcing/sinking strength + 9 + 1 + + + PD15_UH + PD15 ultra high sourcing/sinking strength + 8 + 1 + + + PD14_UH + PD14 ultra high sourcing/sinking strength + 7 + 1 + + + PD13_UH + PD13 ultra high sourcing/sinking strength + 6 + 1 + + + PD12_UH + PD12 ultra high sourcing/sinking strength + 5 + 1 + + + PB10_UH + PB10 ultra high sourcing/sinking strength + 2 + 1 + + + PB9_UH + PB9 ultra high sourcing/sinking strength + 1 + 1 + + + PB3_UH + PB3 ultra high sourcing/sinking strength + 0 + 1 + + + + + + + QSPI1 + Quad SPI Controller + QSPI + 0xA0001000 + + 0x0 + 0x400 + registers + + + QSPI1 + QSPI1 global interrupt + 92 + + + + CMD_W0 + CMD_W0 + Command word 0 + 0x0 + 0x20 + read-write + 0x00000000 + + + SPIADR + SPI flash address + 0 + 32 + + + + + CMD_W1 + CMD_W1 + Command word 1 + 0x4 + 0x20 + read-write + 0x01000003 + + + ADRLEN + SPI address length + 0 + 3 + + + DUM2 + Second dummy state cycle + 16 + 8 + + + INSLEN + Instruction code length + 24 + 2 + + + PEMEN + Perfrmance enhance mode enable + 28 + 1 + + + + + CMD_W2 + CMD_W2 + Command word 2 + 0x8 + 0x20 + read-write + 0x01000003 + + + DCNT + Read write data counter + 0 + 32 + + + + + CMD_W3 + CMD_W3 + Command word 3 + 0xC + 0x20 + read-write + 0x00000000 + + + WEN + Write data enable + 1 + 1 + + + RSTSEN + Read spi status enable + 2 + 1 + + + RSTSC + Read spi status configure + 3 + 1 + + + OPMODE + SPI operate mode + 5 + 3 + + + PEMOPC + Performance enhance mode operate code + 16 + 8 + + + INSC + Instruction code + 24 + 8 + + + + + CTRL + CTRL + Control register + 0x10 + 0x20 + read-write + 0x00000000 + + + CLKDIV + SPI clock divider + 0 + 3 + + + SCKMODE + Sckout mode + 4 + 1 + + + XIPIDLE + XIP port idle status + 7 + 1 + + + ABORT + Abort instruction + 8 + 1 + + + BUSY + Busy bit of spi status + 16 + 3 + + + XIPRCMDF + XIP read command flush + 19 + 1 + + + XIPSEL + XIP port selection + 20 + 1 + + + KEYEN + encryption key enable + 21 + 1 + + + + + ACTR + ACTR + AC timing control register + 0x14 + 0x20 + read-write + 0x0000000F + + + CSDLY + CS delay + 0 + 4 + + + + + FIFOSTS + FIFOSTS + FIFO Status register + 0x18 + 0x20 + read-only + 0x00000001 + + + TXFIFORDY + TxFIFO ready status + 0 + 1 + + + RXFIFORDY + RxFIFO ready status + 1 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x20 + 0x20 + read-write + 0x00000001 + + + DMAEN + DMA handshake enable + 0 + 1 + + + CMDIE + Command complete interrupt enable + 1 + 1 + + + TXFIFOTHOD + TxFIFO thod + 8 + 2 + + + RXFIFOTHOD + RxFIFO thod + 12 + 2 + + + + + CMDSTS + CMDSTS + CMD status register + 0x24 + 0x20 + read-only + 0x00000000 + + + CMDSTS + Command complete status + 0 + 1 + + + + + RSTS + RSTS + SPI read status register + 0x28 + 0x20 + read-only + 0x00000000 + + + SPISTS + SPI read status + 0 + 8 + + + + + FSIZE + FSIZE + SPI flash size + 0x2C + 0x20 + read-write + 0x00000000 + + + SPIFSIZE + SPI flash size + 0 + 32 + + + + + XIP_CMD_W0 + XIP_CMD_W0 + XIP command word 0 + 0x30 + 0x20 + read-write + 0x00000000 + + + XIPR_DUM2 + XIP read second dummy cycle + 0 + 8 + + + XIPR_OPMODE + XIP read operate mode + 8 + 3 + + + XIPR_ADRLEN + XIP read address length + 11 + 1 + + + XIPR_INSC + XIP read instruction code + 12 + 8 + + + + + XIP_CMD_W1 + XIP_CMD_W1 + XIP command word 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + XIPW_DUM2 + XIP write second dummy cycle + 0 + 8 + + + XIPW_OPMODE + XIP write operate mode + 8 + 3 + + + XIPW_ADRLEN + XIP write address length + 11 + 1 + + + XIPW_INSC + XIP write instruction code + 12 + 8 + + + + + XIP_CMD_W2 + XIP_CMD_W2 + XIP command word 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + XIPR_DCNT + XIP read data counter + 0 + 6 + + + XIPR_TCNT + XIP continue read cycle counter + 8 + 7 + + + XIPR_SEL + XIP read continue mode select + 15 + 1 + + + XIPW_DCNT + XIP write data counter + 16 + 6 + + + XIPW_TCNT + XIP continue write cycle counter + 24 + 7 + + + XIPW_SEL + XIP write continue mode select + 31 + 1 + + + + + XIP_CMD_W3 + XIP_CMD_W3 + XIP command word 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + BYPASSC + Bypass cache function + 0 + 1 + + + CSTS + Cache status + 3 + 1 + + + + + REV + REV + Revision + 0x50 + 0x20 + read-write + 0x00010500 + + + REVISION + Revision number + 0 + 31 + + + + + DT + DT + 32/16/8 bit data port register + 0x100 + 0x20 + read-write + 0x00000000 + + + + + QSPI2 + 0xA0002000 + + QSPI2 + QSPI2 global interrupt + 91 + + + + ETHERNET_MAC + Ethernet: media access control + ETHERNET + 0x40028000 + + 0x0 + 0x100 + registers + + + EMAC + Ethernet mac global interrupt + 61 + + + + MACCTRL + MACCTRL + Ethernet MAC configuration register + 0x0 + 0x20 + read-write + 0x00008000 + + + RE + Receiver enable + 2 + 1 + + + TE + Transmitter enable + 3 + 1 + + + DC + Deferral check + 4 + 1 + + + BL + Back-off limit + 5 + 2 + + + ACS + Automatic pad/CRC + stripping + 7 + 1 + + + DR + Disable retry + 9 + 1 + + + IPC + IPv4 checksum offload + 10 + 1 + + + DM + Duplex mode + 11 + 1 + + + LM + Loopback mode + 12 + 1 + + + DRO + Disable receive own + 13 + 1 + + + FES + Fast EMAC speed + 14 + 1 + + + DCS + Disable carrier sense + 16 + 1 + + + IFG + Interframe gap + 17 + 3 + + + JD + Jabber disable + 22 + 1 + + + WD + Watchdog disable + 23 + 1 + + + + + MACFRMF + MACFRMF + Ethernet MAC frame filter register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Promiscuous mode + 0 + 1 + + + HUC + Hash unicast + 1 + 1 + + + HMC + Hash multicast + 2 + 1 + + + DAIF + Destination address inverse + filtering + 3 + 1 + + + PMC + Pass multicast + 4 + 1 + + + DBF + Disable broadcast frames + 5 + 1 + + + PCF + Pass control frames + 6 + 2 + + + SAIF + Source address inverse + filtering + 8 + 1 + + + SAF + Source address filter + 9 + 1 + + + HPF + Hash or perfect filter + 10 + 1 + + + RA + Receive all + 31 + 1 + + + + + MACHTH + MACHTH + Ethernet MAC hash table high register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + Hash table high + 0 + 32 + + + + + MACHTL + MACHTL + Ethernet MAC hash table low register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + Hash table low + 0 + 32 + + + + + MACMIIADDR + MACMIIADDR + Ethernet MAC MII address register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MII busy + 0 + 1 + + + MW + MII write + 1 + 1 + + + CR + Clock range + 2 + 3 + + + MII + MII register + 6 + 5 + + + PA + PHY address + 11 + 5 + + + + + MACMIIDT + MACMIIDT + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + MD + MII data + 0 + 16 + + + + + MACFCTRL + MACFCTRL + Ethernet MAC flow control register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB_BPA + Flow control busy/back pressure + activate + 0 + 1 + + + ETF + Enable transmit flow control + + 1 + 1 + + + ERF + Enable receive flow control + + 2 + 1 + + + DUP + Detect unicast pause frame + 3 + 1 + + + PLT + Pause low threshold + 4 + 2 + + + DZQP + Disable zero-quanta pause + 7 + 1 + + + PT + Pass time + 16 + 16 + + + + + MACVLT + MACVLT + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VTI + VLAN tag identifier (for receive + frames) + 0 + 16 + + + ETV + Enable 12-bit VLAN tag comparison + 16 + 1 + + + + + MACRWFF + MACRWFF + Ethernet MAC remote wakeup frame filter register + 0x28 + 0x20 + read-write + 0x00000000 + + + MACPMTCTRLSTS + MACPMTCTRLSTS + Ethernet MAC PMT control and status register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + Power down + 0 + 1 + + + EMP + Enable magic packet + 1 + 1 + + + ERWF + Enable remote wakeup frame + 2 + 1 + + + RMP + Received magic packet + 5 + 1 + + + RRWF + Recevied remote wakeup frame + 6 + 1 + + + GUC + Global unicast + 9 + 1 + + + RWFFPR + Remote wakeup frame filter register pointer + reset + 31 + 1 + + + + + MACISTS + MACISTS + Ethernet MAC interrupt status register + 0x38 + 0x20 + read-write + 0x00000000 + + + PIS + PMT interrupt status + 3 + 1 + + + MIS + MMC interrupt status + 4 + 1 + + + MRIS + MMC receive interrupt status + 5 + 1 + + + MTIS + MMC transmit interrupt status + 6 + 1 + + + TIS + Timestamp interrupt status + 9 + 1 + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + PIM + PMT interrupt mask + 3 + 1 + + + TIM + Timestamp interrupt mask + 9 + 1 + + + + + MACA0H + MACA0H + Ethernet MAC address 0 high register + 0x40 + 0x20 + 0x0010FFFF + + + MA0H + MAC address0 high + 0 + 16 + read-write + + + AE + Address enable + 31 + 1 + read-only + + + + + MACA0L + MACA0L + Ethernet MAC address 0 low register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MA0L + MAC address0 low + 0 + 32 + + + + + MACA1H + MACA1H + Ethernet MAC address 1 high register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MA1H + MAC address1 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA1L + MACA1L + Ethernet MAC address1 low register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MA1L + MAC address1 low + 0 + 32 + + + + + MACA2H + MACA2H + Ethernet MAC address 2 high register + 0x50 + 0x20 + read-write + 0x0050 + + + MA2H + MAC address 2 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA2L + MACA2L + Ethernet MAC address 2 low register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MA2L + MAC address2 low + 0 + 31 + + + + + MACA3H + MACA3H + Ethernet MAC address 3 high register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MA3H + MAC address3 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA3L + MACA3L + Ethernet MAC address 3 low register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MA3L + MAC address3 low + 0 + 32 + + + + + + + ETHERNET_MMC + Ethernet: MAC management counters + ETHERNET + 0x40028100 + + 0x0 + 0x100 + registers + + + + MMCCTRL + MMCCTRL + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + RC + Reset counter + 0 + 1 + + + SCR + Stop counter rollover + 1 + 1 + + + RR + Reset on read + 2 + 1 + + + FMC + Freeze MMC counter + 31 + 1 + + + + + MMCRI + MMCRI + Ethernet MMC receive interrupt register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCE + Received frames CRC error + 5 + 1 + + + RFAE + Received frames alignment error + 6 + 1 + + + RGUF + Received good unicast frames + 17 + 1 + + + + + MMCTI + MMCTI + Ethernet MMC transmit interrupt register + 0x8 + 0x20 + read-write + 0x00000000 + + + TSCGFCI + Transmit single collision good frame + counter interrupt + 14 + 1 + + + TGFMSC + Transmit good frames more single + collision + 15 + 1 + + + TGF + Transmitted good frames + 21 + 1 + + + + + MMCRIM + MMCRIM + Ethernet MMC receive interrupt mask register + 0xC + 0x20 + read-write + 0x00000000 + + + RCEFCIM + Received CRC error frame counter interrupt + mask + 5 + 1 + + + RAEFACIM + Received alignment error frame alignment + counter interrupt mask + 6 + 1 + + + RUGFCIM + Received unicast good frame counter + interrupt mask + 17 + 1 + + + + + MMCTIM + MMCTIM + Ethernet MMC transmit interrupt mask register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSCGFCIM + Transmit single collision good frame + counter interrupt mask + 14 + 1 + + + TMCGFCIM + Transmit multiple collision good frame + counter interrupt mask + 15 + 1 + + + TGFCIM + Transmitted good frame counter interrupt + mask + 21 + 1 + + + + + MMCTFSCC + MMCTFSCC + Ethernet MMC transmitted good frames after a single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + Transmitted good frames single + collision counter + 0 + 32 + + + + + MMCTFMSCC + MMCTFMSCC + Ethernet MMC transmitted good frames after more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + Transmitted good frame more single + collision counter + 0 + 32 + + + + + MMCTFCNT + MMCTFCNT + Ethernet MMC transmitted good frames counter register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + Transmitted good frames + counter + 0 + 32 + + + + + MMCRFCECNT + MMCRFCECNT + Ethernet MMC received frames with CRC error counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCEC + Received frames CRC error counter + 0 + 32 + + + + + MMCRFAECNT + MMCRFAECNT + Ethernet MMC received frames with alignment error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + Received frames alignment error counter + 0 + 32 + + + + + MMCRGUFCNT + MMCRGUFCNT + MMC received good unicast frames counter register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + Received good unicast frames + counter + 0 + 32 + + + + + + + ETHERNET_PTP + Ethernet: Precision time protocol + ETHERNET + 0x40028700 + + 0x0 + 0x100 + registers + + + + PTPTSCTRL + PTPTSCTRL + Ethernet PTP time stamp control register + 0x0 + 0x20 + read-write + 0x2000 + + + TE + Timestamp enable + 0 + 1 + + + TFCU + Timestamp fine or coarse + update + 1 + 1 + + + TI + Timestamp initialize + 2 + 1 + + + TU + Timestamp update + 3 + 1 + + + TITE + Timestamp interrupt trigger + enable + 4 + 1 + + + ARU + Addend register update + 5 + 1 + + + ETAF + Enable timestamp for all frames + 8 + 1 + + + TDBRC + Timestamp digital or binary + rollover control + 9 + 1 + + + EPPV2F + Enable PTP packet processing for + version2 format + 10 + 1 + + + EPPEF + Enable processing of PTP + over EMAC frames + 11 + 1 + + + EPPFSIP6U + Enable processing of PTP frames + sent over IPv6-UDP + 12 + 1 + + + EPPFSIP4U + Enable processing of PTP frames + sent over IPv4-UDP + 13 + 1 + + + ETSFEM + Enable timestamp snapshot for + event message + 14 + 1 + + + ESFMRTM + Enable snapshot for message + relevant to master + 15 + 1 + + + SPPFTS + Select PTP packet for taking snapshot + 16 + 2 + + + EMAFPFF + Enable MAC address for PTP frame filtering + 18 + 1 + + + + + PTPSSINC + PTPSSINC + Ethernet PTP subsecond increment register + 0x4 + 0x20 + read-write + 0x00000000 + + + SSIV + Sub-second increment value + 0 + 8 + + + + + PTPTSH + PTPTSH + Ethernet PTP time stamp high register + 0x8 + 0x20 + read-only + 0x00000000 + + + TS + Timestamp second + 0 + 32 + + + + + PTPTSL + PTPTSL + Ethernet PTP time stamp low register + 0xC + 0x20 + read-only + 0x00000000 + + + TSS + Timestamp subseconds + 0 + 31 + + + AST + Add or subtract time + 31 + 1 + + + + + PTPTSHUD + PTPTSHUD + Ethernet PTP time stamp high update register + 0x10 + 0x20 + read-write + 0x00000000 + + + TS + Timestamp second + 0 + 32 + + + + + PTPTSLUD + PTPTSLUD + Ethernet PTP time stamp low update register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSS + Timestamp subseconds + 0 + 31 + + + AST + Add or subtract time + 31 + 1 + + + + + PTPTSAD + PTPTSAD + Ethernet PTP time stamp addend register + 0x18 + 0x20 + read-write + 0x00000000 + + + TAR + Timestamp addend register + 0 + 32 + + + + + PTPTTH + PTPTTH + Ethernet PTP target time high register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSR + Target time seconds register + 0 + 32 + + + + + PTPTTL + PTPTTL + Ethernet PTP target time low register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTLR + Target timestamp low register + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSO + Timestamp second overflow + 0 + 1 + + + TTTR + Timestamp target time reached + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control register + 0x2C + 0x20 + read-only + 0x00000000 + + + POFC + PPS Output frequency control + 0 + 4 + + + + + + + ETHERNET_DMA + Ethernet: DMA controller operation + ETHERNET + 0x40029000 + + 0x0 + 0x100 + registers + + + + DMABM + DMABM + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x20101 + + + SWR + Software reset + 0 + 1 + + + DA + DMA Arbitration + 1 + 1 + + + DSL + Descriptor skip length + 2 + 5 + + + PBL + Programmable burst length + 8 + 6 + + + PR + Priority ratio + 14 + 2 + + + FB + Fixed burst + 16 + 1 + + + RDP + Rx DMA PBL + 17 + 6 + + + USP + Use separate PBL + 23 + 1 + + + PBLx8 + PNLx8 mode + 24 + 1 + + + AAB + Address-aligned beats + 25 + 1 + + + + + DMATPD + DMATPD + Ethernet DMA transmit poll demand register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + Transmit poll demand + 0 + 32 + + + + + DMARPD + DMARPD + EHERNET DMA receive poll demand register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + Receive poll demand + 0 + 32 + + + + + DMARDLADDR + DMARDLADDR + Ethernet DMA receive descriptor list address register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + Start of receive list + 0 + 32 + + + + + DMATDLADDR + DMATDLADDR + Ethernet DMA transmit descriptor list address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + Start of transmit list + 0 + 32 + + + + + DMASTS + DMASTS + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TI + Transmit interrupt + 0 + 1 + read-write + + + TPS + Transmit process stopped + 1 + 1 + read-write + + + TBU + Transmit buffer unavailable + 2 + 1 + read-write + + + TJT + Transmit jabber timeout + 3 + 1 + read-write + + + OVF + Receive overflow + 4 + 1 + read-write + + + UNF + Transmit underflow + 5 + 1 + read-write + + + RI + Receive interrupt + 6 + 1 + read-write + + + RBU + Receive buffer unavailable + 7 + 1 + read-write + + + RPS + Receive process stopped + 8 + 1 + read-write + + + RWT + Receive watchdog timeout + 9 + 1 + read-write + + + ETI + Early transmit interrupt + 10 + 1 + read-write + + + FBEI + Fatal bus error interrupt + 13 + 1 + read-write + + + ERI + Early receive interrupt + 14 + 1 + read-write + + + AIS + Abnormal interrupt summary + 15 + 1 + read-write + + + NIS + Normal interrupt summary + 16 + 1 + read-write + + + RS + Receive process state + 17 + 3 + read-only + + + TS + Transmit process state + 20 + 3 + read-only + + + EB + Error bits + 23 + 3 + read-only + + + MMI + MAC MMC interrupt + 27 + 1 + read-only + + + MPI + MAC PMT interrupt + 28 + 1 + read-only + + + TTI + Timestamp trigger interrupt + 29 + 1 + read-only + + + + + DMAOPM + DMAOPM + Ethernet DMA operation mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + SSR + Start or stop receive + 1 + 1 + + + OSF + Operate on second frame + 2 + 1 + + + RTC + Receive threshold control + 3 + 2 + + + FUGF + Forward undersized good frames + 6 + 1 + + + FEF + Forward error frames + 7 + 1 + + + SSTC + Start of stop transmission command + 13 + 1 + + + TTC + Transmit threshold control + 14 + 3 + + + FTF + Flush transmit FIFO + 20 + 1 + + + TSF + Transmit store and forward + 21 + 1 + + + DFRF + Disable flushing of received + frames + 24 + 1 + + + RSF + Receive store and forward + 25 + 1 + + + DT + Disable dropping of TCP/IP + checksum error frames + 26 + 1 + + + + + DMAIE + DMAIE + Ethernet DMA interrupt enable register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + Transmit interrupt enable + 0 + 1 + + + TSE + Transmit stopped enable + 1 + 1 + + + TUE + Transmit buffer unavailable enable + 2 + 1 + + + TJE + Transmit jabber timeout enable + 3 + 1 + + + OVE + Overflow interrupt enable + 4 + 1 + + + UNE + Underflow interrupt enable + 5 + 1 + + + RIE + Receive interrupt enable + 6 + 1 + + + RBUE + Receive buffer unavailable enable + 7 + 1 + + + RSE + Receive stopped enable + 8 + 1 + + + RWTE + receive watchdog timeout enable + 9 + 1 + + + EIE + Early transmit interrupt enable + 10 + 1 + + + FBEE + Fatal bus error enable + 13 + 1 + + + ERE + Early receive interrupt + enable + 14 + 1 + + + AIE + Abnormal interrupt enable + 15 + 1 + + + NIE + Normal interrupt enable + 16 + 1 + + + + + DMAMFBOCNT + DMAMFBOCNT + Ethernet DMA missed frame and buffer overflow counter register + 0x20 + 0x20 + read-only + 0x00000000 + + + MFC + Missed frames control + 0 + 16 + + + OBMFC + Overflow bit for missed frame + counter + 16 + 1 + + + OFC + Overflow frame counter + 17 + 11 + + + OBFOC + Overflow bit for FIFO overflow + counter + 28 + 1 + + + + + DMACTD + DMACTD + Ethernet DMA current host transmit descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + Host transmit descriptor address pointer + 0 + 32 + + + + + DMACRD + DMACRD + Ethernet DMA current host receive descriptor register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + Host receive descriptor address pointer + 0 + 32 + + + + + DMACTBADDR + DMACTBADDR + Ethernet DMA current host transmit buffer address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + Host transmit buffer address pointer + 0 + 32 + + + + + DMACRBADDR + DMACRBADDR + Ethernet DMA current host receive buffer address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + Host receive buffer address pointer + 0 + 32 + + + + + + + diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h new file mode 100644 index 0000000000..aa3c70d768 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h @@ -0,0 +1,205 @@ +/** + ************************************************************************** + * @file at32f435_437_acc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 acc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_ACC_H +#define __AT32F435_437_ACC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup ACC + * @{ + */ + +/** @defgroup ACC_exported_constants + * @{ + */ + +#define ACC_CAL_HICKCAL ((uint16_t)0x0000) /*!< acc hick calibration */ +#define ACC_CAL_HICKTRIM ((uint16_t)0x0002) /*!< acc hick trim */ + +#define ACC_RSLOST_FLAG ((uint16_t)0x0002) /*!< acc reference signal lost error flag */ +#define ACC_CALRDY_FLAG ((uint16_t)0x0001) /*!< acc internal high-speed clock calibration ready error flag */ + +#define ACC_CALRDYIEN_INT ((uint16_t)0x0020) /*!< acc internal high-speed clock calibration ready interrupt enable */ +#define ACC_EIEN_INT ((uint16_t)0x0010) /*!< acc reference signal lost interrupt enable */ + +#define ACC_SOF_OTG1 ((uint16_t)0x0000) /*!< acc sof signal select: otg1 */ +#define ACC_SOF_OTG2 ((uint16_t)0x0004) /*!< acc sof signal select: otg2 */ + +/** + * @} + */ + +/** @defgroup ACC_exported_types + * @{ + */ + +/** + * @brief type define acc register all + */ +typedef struct +{ + + /** + * @brief acc sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t calrdy : 1; /* [0] */ + __IO uint32_t rslost : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } sts_bit; + }; + + /** + * @brief acc ctrl1 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t calon : 1; /* [0] */ + __IO uint32_t entrim : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t eien : 1; /* [4] */ + __IO uint32_t calrdyien : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t step : 4; /* [11:8] */ + __IO uint32_t reserved3 : 20;/* [31:12] */ + } ctrl1_bit; + }; + + /** + * @brief acc ctrl2 register, offset:0x08 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t hickcal : 8; /* [7:0] */ + __IO uint32_t hicktrim : 6; /* [13:8] */ + __IO uint32_t reserved1 : 18;/* [31:14] */ + } ctrl2_bit; + }; + + /** + * @brief acc acc_c1 register, offset:0x0C + */ + union + { + __IO uint32_t c1; + struct + { + __IO uint32_t c1 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c1_bit; + }; + + /** + * @brief acc acc_c2 register, offset:0x10 + */ + union + { + __IO uint32_t c2; + struct + { + __IO uint32_t c2 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c2_bit; + }; + + /** + * @brief acc acc_c3 register, offset:0x14 + */ + union + { + __IO uint32_t c3; + struct + { + __IO uint32_t c3 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c3_bit; + }; +} acc_type; + +/** + * @} + */ + +#define ACC ((acc_type *) ACC_BASE) + +/** @defgroup ACC_exported_functions + * @{ + */ + +void acc_calibration_mode_enable(uint16_t acc_trim, confirm_state new_state); +void acc_step_set(uint8_t step_value); +void acc_sof_select(uint16_t sof_sel); +void acc_interrupt_enable(uint16_t acc_int, confirm_state new_state); +uint8_t acc_hicktrim_get(void); +uint8_t acc_hickcal_get(void); +void acc_write_c1(uint16_t acc_c1_value); +void acc_write_c2(uint16_t acc_c2_value); +void acc_write_c3(uint16_t acc_c3_value); +uint16_t acc_read_c1(void); +uint16_t acc_read_c2(void); +uint16_t acc_read_c3(void); +flag_status acc_flag_get(uint16_t acc_flag); +void acc_flag_clear(uint16_t acc_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h new file mode 100644 index 0000000000..1232495c8e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h @@ -0,0 +1,938 @@ +/** + ************************************************************************** + * @file at32f435_437_adc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 adc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_ADC_H +#define __AT32F435_437_ADC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/** @defgroup ADC_interrupts_definition + * @brief adc interrupt + * @{ + */ + +#define ADC_OCCE_INT ((uint32_t)0x00000020) /*!< ordinary channels conversion end interrupt */ +#define ADC_VMOR_INT ((uint32_t)0x00000040) /*!< voltage monitoring out of range interrupt */ +#define ADC_PCCE_INT ((uint32_t)0x00000080) /*!< preempt channels conversion end interrupt */ +#define ADC_OCCO_INT ((uint32_t)0x04000000) /*!< ordinary channel conversion overflow interrupt */ + +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @brief adc flag + * @{ + */ + +#define ADC_VMOR_FLAG ((uint8_t)0x01) /*!< voltage monitoring out of range flag */ +#define ADC_OCCE_FLAG ((uint8_t)0x02) /*!< ordinary channels conversion end flag */ +#define ADC_PCCE_FLAG ((uint8_t)0x04) /*!< preempt channels conversion end flag */ +#define ADC_PCCS_FLAG ((uint8_t)0x08) /*!< preempt channel conversion start flag */ +#define ADC_OCCS_FLAG ((uint8_t)0x10) /*!< ordinary channel conversion start flag */ +#define ADC_OCCO_FLAG ((uint8_t)0x20) /*!< ordinary channel conversion overflow flag */ +#define ADC_RDY_FLAG ((uint8_t)0x40) /*!< adc ready to conversion flag */ + +/** + * @} + */ + +/** @defgroup ADC_exported_types + * @{ + */ + +/** + * @brief adc division type + */ +typedef enum +{ + ADC_HCLK_DIV_2 = 0x00, /*!< adcclk is hclk/2 */ + ADC_HCLK_DIV_3 = 0x01, /*!< adcclk is hclk/3 */ + ADC_HCLK_DIV_4 = 0x02, /*!< adcclk is hclk/4 */ + ADC_HCLK_DIV_5 = 0x03, /*!< adcclk is hclk/5 */ + ADC_HCLK_DIV_6 = 0x04, /*!< adcclk is hclk/6 */ + ADC_HCLK_DIV_7 = 0x05, /*!< adcclk is hclk/7 */ + ADC_HCLK_DIV_8 = 0x06, /*!< adcclk is hclk/8 */ + ADC_HCLK_DIV_9 = 0x07, /*!< adcclk is hclk/9 */ + ADC_HCLK_DIV_10 = 0x08, /*!< adcclk is hclk/10 */ + ADC_HCLK_DIV_11 = 0x09, /*!< adcclk is hclk/11 */ + ADC_HCLK_DIV_12 = 0x0A, /*!< adcclk is hclk/12 */ + ADC_HCLK_DIV_13 = 0x0B, /*!< adcclk is hclk/13 */ + ADC_HCLK_DIV_14 = 0x0C, /*!< adcclk is hclk/14 */ + ADC_HCLK_DIV_15 = 0x0D, /*!< adcclk is hclk/15 */ + ADC_HCLK_DIV_16 = 0x0E, /*!< adcclk is hclk/16 */ + ADC_HCLK_DIV_17 = 0x0F /*!< adcclk is hclk/17 */ +} adc_div_type; + +/** + * @brief adc combine mode type + */ +typedef enum +{ + ADC_INDEPENDENT_MODE = 0x00, /*!< independent mode */ + ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE = 0x01, /*!< single slaver combined ordinary simultaneous + preempt simultaneous mode */ + ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE = 0x02, /*!< single slaver combined ordinary simultaneous + preempt interleaved trigger mode */ + ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE = 0x05, /*!< single slaver preempt simultaneous mode only */ + ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE = 0x06, /*!< single slaver ordinary simultaneous mode only */ + ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE = 0x07, /*!< single slaver ordinary shifting mode only */ + ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE = 0x09, /*!< single slaver preempt interleaved trigger mode only */ + ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE = 0x11, /*!< double slaver combined ordinary simultaneous + preempt simultaneous mode */ + ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE = 0x12, /*!< double slaver combined ordinary simultaneous + preempt interleaved trigger mode */ + ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE = 0x15, /*!< double slaver preempt simultaneous mode only */ + ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE = 0x16, /*!< double slaver ordinary simultaneous mode only */ + ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE = 0x17, /*!< double slaver ordinary shifting mode only */ + ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE = 0x19 /*!< double slaver preempt interleaved trigger mode only */ +} adc_combine_mode_type; + +/** + * @brief adc common dma mode type + */ +typedef enum +{ + ADC_COMMON_DMAMODE_DISABLE = 0x00, /*!< dma mode disabled */ + ADC_COMMON_DMAMODE_1 = 0x01, /*!< dma mode1: each dma request trans a half-word data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_2 = 0x02, /*!< dma mode2: each dma request trans two half-word data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_3 = 0x03, /*!< dma mode3: each dma request trans two bytes data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_4 = 0x04, /*!< dma mode4: each dma request trans three bytes data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_5 = 0x05 /*!< dma mode5: odd dma request trans two half-word data,even dma request trans a half-word data(reference manual account the rule of data package) */ +} adc_common_dma_mode_type; + +/** + * @brief adc common sampling interval type + */ +typedef enum +{ + ADC_SAMPLING_INTERVAL_5CYCLES = 0x00, /*!< ordinary shifting mode adjacent adc sampling interval 5 adcclk */ + ADC_SAMPLING_INTERVAL_6CYCLES = 0x01, /*!< ordinary shifting mode adjacent adc sampling interval 6 adcclk */ + ADC_SAMPLING_INTERVAL_7CYCLES = 0x02, /*!< ordinary shifting mode adjacent adc sampling interval 7 adcclk */ + ADC_SAMPLING_INTERVAL_8CYCLES = 0x03, /*!< ordinary shifting mode adjacent adc sampling interval 8 adcclk */ + ADC_SAMPLING_INTERVAL_9CYCLES = 0x04, /*!< ordinary shifting mode adjacent adc sampling interval 9 adcclk */ + ADC_SAMPLING_INTERVAL_10CYCLES = 0x05, /*!< ordinary shifting mode adjacent adc sampling interval 10 adcclk */ + ADC_SAMPLING_INTERVAL_11CYCLES = 0x06, /*!< ordinary shifting mode adjacent adc sampling interval 11 adcclk */ + ADC_SAMPLING_INTERVAL_12CYCLES = 0x07, /*!< ordinary shifting mode adjacent adc sampling interval 12 adcclk */ + ADC_SAMPLING_INTERVAL_13CYCLES = 0x08, /*!< ordinary shifting mode adjacent adc sampling interval 13 adcclk */ + ADC_SAMPLING_INTERVAL_14CYCLES = 0x09, /*!< ordinary shifting mode adjacent adc sampling interval 14 adcclk */ + ADC_SAMPLING_INTERVAL_15CYCLES = 0x0A, /*!< ordinary shifting mode adjacent adc sampling interval 15 adcclk */ + ADC_SAMPLING_INTERVAL_16CYCLES = 0x0B, /*!< ordinary shifting mode adjacent adc sampling interval 16 adcclk */ + ADC_SAMPLING_INTERVAL_17CYCLES = 0x0C, /*!< ordinary shifting mode adjacent adc sampling interval 17 adcclk */ + ADC_SAMPLING_INTERVAL_18CYCLES = 0x0D, /*!< ordinary shifting mode adjacent adc sampling interval 18 adcclk */ + ADC_SAMPLING_INTERVAL_19CYCLES = 0x0E, /*!< ordinary shifting mode adjacent adc sampling interval 19 adcclk */ + ADC_SAMPLING_INTERVAL_20CYCLES = 0x0F /*!< ordinary shifting mode adjacent adc sampling interval 20 adcclk */ +} adc_sampling_interval_type; + +/** + * @brief adc conversion resolution type + */ +typedef enum +{ + ADC_RESOLUTION_12B = 0x00, /*!< conversion resolution 12 bit */ + ADC_RESOLUTION_10B = 0x01, /*!< conversion resolution 10 bit */ + ADC_RESOLUTION_8B = 0x02, /*!< conversion resolution 8 bit */ + ADC_RESOLUTION_6B = 0x03 /*!< conversion resolution 6 bit */ +} adc_resolution_type; + +/** + * @brief adc data align type + */ +typedef enum +{ + ADC_RIGHT_ALIGNMENT = 0x00, /*!< data right alignment */ + ADC_LEFT_ALIGNMENT = 0x01 /*!< data left alignment */ +} adc_data_align_type; + +/** + * @brief adc channel select type + */ +typedef enum +{ + ADC_CHANNEL_0 = 0x00, /*!< adc channel 0 */ + ADC_CHANNEL_1 = 0x01, /*!< adc channel 1 */ + ADC_CHANNEL_2 = 0x02, /*!< adc channel 2 */ + ADC_CHANNEL_3 = 0x03, /*!< adc channel 3 */ + ADC_CHANNEL_4 = 0x04, /*!< adc channel 4 */ + ADC_CHANNEL_5 = 0x05, /*!< adc channel 5 */ + ADC_CHANNEL_6 = 0x06, /*!< adc channel 6 */ + ADC_CHANNEL_7 = 0x07, /*!< adc channel 7 */ + ADC_CHANNEL_8 = 0x08, /*!< adc channel 8 */ + ADC_CHANNEL_9 = 0x09, /*!< adc channel 9 */ + ADC_CHANNEL_10 = 0x0A, /*!< adc channel 10 */ + ADC_CHANNEL_11 = 0x0B, /*!< adc channel 11 */ + ADC_CHANNEL_12 = 0x0C, /*!< adc channel 12 */ + ADC_CHANNEL_13 = 0x0D, /*!< adc channel 13 */ + ADC_CHANNEL_14 = 0x0E, /*!< adc channel 14 */ + ADC_CHANNEL_15 = 0x0F, /*!< adc channel 15 */ + ADC_CHANNEL_16 = 0x10, /*!< adc channel 16 */ + ADC_CHANNEL_17 = 0x11, /*!< adc channel 17 */ + ADC_CHANNEL_18 = 0x12 /*!< adc channel 18 */ +} adc_channel_select_type; + +/** + * @brief adc sampletime select type + */ +typedef enum +{ + ADC_SAMPLETIME_2_5 = 0x00, /*!< adc sample time 2.5 cycle */ + ADC_SAMPLETIME_6_5 = 0x01, /*!< adc sample time 6.5 cycle */ + ADC_SAMPLETIME_12_5 = 0x02, /*!< adc sample time 12.5 cycle */ + ADC_SAMPLETIME_24_5 = 0x03, /*!< adc sample time 24.5 cycle */ + ADC_SAMPLETIME_47_5 = 0x04, /*!< adc sample time 47.5 cycle */ + ADC_SAMPLETIME_92_5 = 0x05, /*!< adc sample time 92.5 cycle */ + ADC_SAMPLETIME_247_5 = 0x06, /*!< adc sample time 247.5 cycle */ + ADC_SAMPLETIME_640_5 = 0x07 /*!< adc sample time 640.5 cycle */ +} adc_sampletime_select_type; + +/** + * @brief adc ordinary group trigger event select type + */ +typedef enum +{ + ADC_ORDINARY_TRIG_TMR1CH1 = 0x00, /*!< timer1 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1CH2 = 0x01, /*!< timer1 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1CH3 = 0x02, /*!< timer1 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH2 = 0x03, /*!< timer2 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH3 = 0x04, /*!< timer2 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH4 = 0x05, /*!< timer2 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2TRGOUT = 0x06, /*!< timer2 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3CH1 = 0x07, /*!< timer3 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3TRGOUT = 0x08, /*!< timer3 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4CH4 = 0x09, /*!< timer4 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH1 = 0x0A, /*!< timer5 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH2 = 0x0B, /*!< timer5 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH3 = 0x0C, /*!< timer5 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8CH1 = 0x0D, /*!< timer8 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8TRGOUT = 0x0E, /*!< timer8 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_EXINT11 = 0x0F, /*!< exint line11 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20TRGOUT = 0x10, /*!< timer20 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20TRGOUT2 = 0x11, /*!< timer20 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH1 = 0x12, /*!< timer20 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH2 = 0x13, /*!< timer20 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH3 = 0x14, /*!< timer20 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8TRGOUT2 = 0x15, /*!< timer8 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1TRGOUT2 = 0x16, /*!< timer1 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4TRGOUT = 0x17, /*!< timer4 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR6TRGOUT = 0x18, /*!< timer6 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3CH4 = 0x19, /*!< timer3 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4CH1 = 0x1A, /*!< timer4 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1TRGOUT = 0x1B, /*!< timer1 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH1 = 0x1C, /*!< timer2 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR7TRGOUT = 0x1E /*!< timer7 trgout event as trigger source of ordinary sequence */ +} adc_ordinary_trig_select_type; + +/** + * @brief adc ordinary channel conversion's external_trigger_edge type + */ +typedef enum +{ + ADC_ORDINARY_TRIG_EDGE_NONE = 0x00, /*!< ordinary channels trigger detection disabled */ + ADC_ORDINARY_TRIG_EDGE_RISING = 0x01, /*!< ordinary channels trigger detection on the rising edge */ + ADC_ORDINARY_TRIG_EDGE_FALLING = 0x02, /*!< ordinary channels trigger detection on the falling edge */ + ADC_ORDINARY_TRIG_EDGE_RISING_FALLING = 0x03 /*!< ordinary channels trigger detection on both the rising and falling edges */ +} adc_ordinary_trig_edge_type; + +/** + * @brief adc preempt group external trigger event select type + */ +typedef enum +{ + ADC_PREEMPT_TRIG_TMR1CH4 = 0x00, /*!< timer1 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1TRGOUT = 0x01, /*!< timer1 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR2CH1 = 0x02, /*!< timer2 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR2TRGOUT = 0x03, /*!< timer2 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH2 = 0x04, /*!< timer3 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH4 = 0x05, /*!< timer3 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH1 = 0x06, /*!< timer4 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH2 = 0x07, /*!< timer4 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH3 = 0x08, /*!< timer4 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4TRGOUT = 0x09, /*!< timer4 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR5CH4 = 0x0A, /*!< timer5 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR5TRGOUT = 0x0B, /*!< timer5 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH2 = 0x0C, /*!< timer8 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH3 = 0x0D, /*!< timer8 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH4 = 0x0E, /*!< timer8 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_EXINT15 = 0x0F, /*!< exint line15 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20TRGOUT = 0x10, /*!< timer20 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20TRGOUT2 = 0x11, /*!< timer20 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20CH4 = 0x12, /*!< timer20 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1TRGOUT2 = 0x13, /*!< timer1 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8TRGOUT = 0x14, /*!< timer8 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8TRGOUT2 = 0x15, /*!< timer8 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH3 = 0x16, /*!< timer3 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3TRGOUT = 0x17, /*!< timer3 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH1 = 0x18, /*!< timer3 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR6TRGOUT = 0x19, /*!< timer6 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH4 = 0x1A, /*!< timer4 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1CH3 = 0x1B, /*!< timer1 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20CH2 = 0x1C, /*!< timer20 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR7TRGOUT = 0x1E /*!< timer7 trgout event as trigger source of preempt sequence */ +} adc_preempt_trig_select_type; + +/** + * @brief adc preempt channel conversion's external_trigger_edge type + */ +typedef enum +{ + ADC_PREEMPT_TRIG_EDGE_NONE = 0x00, /*!< preempt channels trigger detection disabled */ + ADC_PREEMPT_TRIG_EDGE_RISING = 0x01, /*!< preempt channels trigger detection on the rising edge */ + ADC_PREEMPT_TRIG_EDGE_FALLING = 0x02, /*!< preempt channels trigger detection on the falling edge */ + ADC_PREEMPT_TRIG_EDGE_RISING_FALLING = 0x03 /*!< preempt channels trigger detection on both the rising and falling edges */ +} adc_preempt_trig_edge_type; + +/** + * @brief adc preempt channel type + */ +typedef enum +{ + ADC_PREEMPT_CHANNEL_1 = 0x00, /*!< adc preempt channel 1 */ + ADC_PREEMPT_CHANNEL_2 = 0x01, /*!< adc preempt channel 2 */ + ADC_PREEMPT_CHANNEL_3 = 0x02, /*!< adc preempt channel 3 */ + ADC_PREEMPT_CHANNEL_4 = 0x03 /*!< adc preempt channel 4 */ +} adc_preempt_channel_type; + +/** + * @brief adc voltage_monitoring type + */ +typedef enum +{ + ADC_VMONITOR_SINGLE_ORDINARY = 0x00800200, /*!< voltage_monitoring on a single ordinary channel */ + ADC_VMONITOR_SINGLE_PREEMPT = 0x00400200, /*!< voltage_monitoring on a single preempt channel */ + ADC_VMONITOR_SINGLE_ORDINARY_PREEMPT = 0x00C00200, /*!< voltage_monitoring on a single ordinary or preempt channel */ + ADC_VMONITOR_ALL_ORDINARY = 0x00800000, /*!< voltage_monitoring on all ordinary channel */ + ADC_VMONITOR_ALL_PREEMPT = 0x00400000, /*!< voltage_monitoring on all preempt channel */ + ADC_VMONITOR_ALL_ORDINARY_PREEMPT = 0x00C00000, /*!< voltage_monitoring on all ordinary and preempt channel */ + ADC_VMONITOR_NONE = 0x00000000 /*!< no channel guarded by the voltage_monitoring */ +} adc_voltage_monitoring_type; + +/** + * @brief adc oversample ratio type + */ +typedef enum +{ + ADC_OVERSAMPLE_RATIO_2 = 0x00, /*!< adc oversample ratio 2 */ + ADC_OVERSAMPLE_RATIO_4 = 0x01, /*!< adc oversample ratio 4 */ + ADC_OVERSAMPLE_RATIO_8 = 0x02, /*!< adc oversample ratio 8 */ + ADC_OVERSAMPLE_RATIO_16 = 0x03, /*!< adc oversample ratio 16 */ + ADC_OVERSAMPLE_RATIO_32 = 0x04, /*!< adc oversample ratio 32 */ + ADC_OVERSAMPLE_RATIO_64 = 0x05, /*!< adc oversample ratio 64 */ + ADC_OVERSAMPLE_RATIO_128 = 0x06, /*!< adc oversample ratio 128 */ + ADC_OVERSAMPLE_RATIO_256 = 0x07 /*!< adc oversample ratio 256 */ +} adc_oversample_ratio_type; + +/** + * @brief adc oversample shift type + */ +typedef enum +{ + ADC_OVERSAMPLE_SHIFT_0 = 0x00, /*!< adc oversample shift 0 */ + ADC_OVERSAMPLE_SHIFT_1 = 0x01, /*!< adc oversample shift 1 */ + ADC_OVERSAMPLE_SHIFT_2 = 0x02, /*!< adc oversample shift 2 */ + ADC_OVERSAMPLE_SHIFT_3 = 0x03, /*!< adc oversample shift 3 */ + ADC_OVERSAMPLE_SHIFT_4 = 0x04, /*!< adc oversample shift 4 */ + ADC_OVERSAMPLE_SHIFT_5 = 0x05, /*!< adc oversample shift 5 */ + ADC_OVERSAMPLE_SHIFT_6 = 0x06, /*!< adc oversample shift 6 */ + ADC_OVERSAMPLE_SHIFT_7 = 0x07, /*!< adc oversample shift 7 */ + ADC_OVERSAMPLE_SHIFT_8 = 0x08 /*!< adc oversample shift 8 */ +} adc_oversample_shift_type; + +/** + * @brief adc ordinary oversample recover type + */ +typedef enum +{ + ADC_OVERSAMPLE_CONTINUE = 0x00, /*!< continue mode:when preempt triggered,oversampling is temporary stopped and continued after preempt sequence */ + ADC_OVERSAMPLE_RESTART = 0x01 /*!< restart mode:when preempt triggered,oversampling is aborted and resumed from start after preempt sequence */ +} adc_ordinary_oversample_restart_type; + +/** + * @brief adc common config type + */ +typedef struct +{ + adc_combine_mode_type combine_mode; /*!< adc combine mode select */ + adc_div_type div; /*!< adc division select */ + adc_common_dma_mode_type common_dma_mode; /*!< adc common dma mode select */ + confirm_state common_dma_request_repeat_state; /*!< adc common dma repeat state */ + adc_sampling_interval_type sampling_interval; /*!< ordinary shifting mode adjacent adc sampling interval select */ + confirm_state tempervintrv_state; /*!< adc temperature sensor and vintrv state */ + confirm_state vbat_state; /*!< adc voltage battery state */ +} adc_common_config_type; + +/** + * @brief adc base config type + */ +typedef struct +{ + confirm_state sequence_mode; /*!< adc sequence mode */ + confirm_state repeat_mode; /*!< adc repeat mode */ + adc_data_align_type data_align; /*!< adc data alignment */ + uint8_t ordinary_channel_length; /*!< adc ordinary channel sequence length*/ +} adc_base_config_type; + +/** + * @brief type define adc register all + */ +typedef struct +{ + + /** + * @brief adc sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t vmor : 1; /* [0] */ + __IO uint32_t occe : 1; /* [1] */ + __IO uint32_t pcce : 1; /* [2] */ + __IO uint32_t pccs : 1; /* [3] */ + __IO uint32_t occs : 1; /* [4] */ + __IO uint32_t occo : 1; /* [5] */ + __IO uint32_t rdy : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } sts_bit; + }; + + /** + * @brief adc ctrl1 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t vmcsel : 5; /* [4:0] */ + __IO uint32_t occeien : 1; /* [5] */ + __IO uint32_t vmorien : 1; /* [6] */ + __IO uint32_t pcceien : 1; /* [7] */ + __IO uint32_t sqen : 1; /* [8] */ + __IO uint32_t vmsgen : 1; /* [9] */ + __IO uint32_t pcautoen : 1; /* [10] */ + __IO uint32_t ocpen : 1; /* [11] */ + __IO uint32_t pcpen : 1; /* [12] */ + __IO uint32_t ocpcnt : 3; /* [15:13] */ + __IO uint32_t reserved1 : 6; /* [21:16] */ + __IO uint32_t pcvmen : 1; /* [22] */ + __IO uint32_t ocvmen : 1; /* [23] */ + __IO uint32_t crsel : 2; /* [25:24] */ + __IO uint32_t occoien : 1; /* [26] */ + __IO uint32_t reserved2 : 5; /* [31:27] */ + } ctrl1_bit; + }; + + /** + * @brief adc ctrl2 register, offset:0x08 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t adcen : 1; /* [0] */ + __IO uint32_t rpen : 1; /* [1] */ + __IO uint32_t adcal : 1; /* [2] */ + __IO uint32_t adcalinit : 1; /* [3] */ + __IO uint32_t adabrt : 1; /* [4] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t ocdmaen : 1; /* [8] */ + __IO uint32_t ocdrcen : 1; /* [9] */ + __IO uint32_t eocsfen : 1; /* [10] */ + __IO uint32_t dtalign : 1; /* [11] */ + __IO uint32_t reserved2 : 4; /* [15:12] */ + __IO uint32_t pctesel_l : 4; /* [19:16] */ + __IO uint32_t pcete : 2; /* [21:20] */ + __IO uint32_t pcswtrg : 1; /* [22] */ + __IO uint32_t pctesel_h : 1; /* [23] */ + __IO uint32_t octesel_l : 4; /* [27:24] */ + __IO uint32_t ocete : 2; /* [29:28] */ + __IO uint32_t ocswtrg : 1; /* [30] */ + __IO uint32_t octesel_h : 1; /* [31] */ + } ctrl2_bit; + }; + + /** + * @brief adc spt1 register, offset:0x0C + */ + union + { + __IO uint32_t spt1; + struct + { + __IO uint32_t cspt10 : 3; /* [2:0] */ + __IO uint32_t cspt11 : 3; /* [5:3] */ + __IO uint32_t cspt12 : 3; /* [8:6] */ + __IO uint32_t cspt13 : 3; /* [11:9] */ + __IO uint32_t cspt14 : 3; /* [14:12] */ + __IO uint32_t cspt15 : 3; /* [17:15] */ + __IO uint32_t cspt16 : 3; /* [20:18] */ + __IO uint32_t cspt17 : 3; /* [23:21] */ + __IO uint32_t cspt18 : 3; /* [26:24] */ + __IO uint32_t reserved1 : 5;/* [31:27] */ + } spt1_bit; + }; + + /** + * @brief adc spt2 register, offset:0x10 + */ + union + { + __IO uint32_t spt2; + struct + { + __IO uint32_t cspt0 : 3;/* [2:0] */ + __IO uint32_t cspt1 : 3;/* [5:3] */ + __IO uint32_t cspt2 : 3;/* [8:6] */ + __IO uint32_t cspt3 : 3;/* [11:9] */ + __IO uint32_t cspt4 : 3;/* [14:12] */ + __IO uint32_t cspt5 : 3;/* [17:15] */ + __IO uint32_t cspt6 : 3;/* [20:18] */ + __IO uint32_t cspt7 : 3;/* [23:21] */ + __IO uint32_t cspt8 : 3;/* [26:24] */ + __IO uint32_t cspt9 : 3;/* [29:27] */ + __IO uint32_t reserved1 : 2;/* [31:30] */ + } spt2_bit; + }; + + /** + * @brief adc pcdto1 register, offset:0x14 + */ + union + { + __IO uint32_t pcdto1; + struct + { + __IO uint32_t pcdto1 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto1_bit; + }; + + /** + * @brief adc pcdto2 register, offset:0x18 + */ + union + { + __IO uint32_t pcdto2; + struct + { + __IO uint32_t pcdto2 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto2_bit; + }; + + /** + * @brief adc pcdto3 register, offset:0x1C + */ + union + { + __IO uint32_t pcdto3; + struct + { + __IO uint32_t pcdto3 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto3_bit; + }; + + /** + * @brief adc pcdto4 register, offset:0x20 + */ + union + { + __IO uint32_t pcdto4; + struct + { + __IO uint32_t pcdto4 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto4_bit; + }; + + /** + * @brief adc vmhb register, offset:0x24 + */ + union + { + __IO uint32_t vmhb; + struct + { + __IO uint32_t vmhb : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } vmhb_bit; + }; + + /** + * @brief adc vmlb register, offset:0x28 + */ + union + { + __IO uint32_t vmlb; + struct + { + __IO uint32_t vmlb : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } vmlb_bit; + }; + + /** + * @brief adc osq1 register, offset:0x2C + */ + union + { + __IO uint32_t osq1; + struct + { + __IO uint32_t osn13 : 5; /* [4:0] */ + __IO uint32_t osn14 : 5; /* [9:5] */ + __IO uint32_t osn15 : 5; /* [14:10] */ + __IO uint32_t osn16 : 5; /* [19:15] */ + __IO uint32_t oclen : 4; /* [23:20] */ + __IO uint32_t reserved1 : 8; /* [31:24] */ + } osq1_bit; + }; + + /** + * @brief adc osq2 register, offset:0x30 + */ + union + { + __IO uint32_t osq2; + struct + { + __IO uint32_t osn7 : 5; /* [4:0] */ + __IO uint32_t osn8 : 5; /* [9:5] */ + __IO uint32_t osn9 : 5; /* [14:10] */ + __IO uint32_t osn10 : 5; /* [19:15] */ + __IO uint32_t osn11 : 5; /* [24:20] */ + __IO uint32_t osn12 : 5; /* [29:25] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } osq2_bit; + }; + + /** + * @brief adc osq3 register, offset:0x34 + */ + union + { + __IO uint32_t osq3; + struct + { + __IO uint32_t osn1 : 5; /* [4:0] */ + __IO uint32_t osn2 : 5; /* [9:5] */ + __IO uint32_t osn3 : 5; /* [14:10] */ + __IO uint32_t osn4 : 5; /* [19:15] */ + __IO uint32_t osn5 : 5; /* [24:20] */ + __IO uint32_t osn6 : 5; /* [29:25] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } osq3_bit; + }; + + /** + * @brief adc psq register, offset:0x38 + */ + union + { + __IO uint32_t psq; + struct + { + __IO uint32_t psn1 : 5; /* [4:0] */ + __IO uint32_t psn2 : 5; /* [9:5] */ + __IO uint32_t psn3 : 5; /* [14:10] */ + __IO uint32_t psn4 : 5; /* [19:15] */ + __IO uint32_t pclen : 2; /* [21:20] */ + __IO uint32_t reserved1 : 10;/* [31:22] */ + } psq_bit; + }; + + /** + * @brief adc pdt1 register, offset:0x3C + */ + union + { + __IO uint32_t pdt1; + struct + { + __IO uint32_t pdt1 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt1_bit; + }; + + /** + * @brief adc pdt2 register, offset:0x40 + */ + union + { + __IO uint32_t pdt2; + struct + { + __IO uint32_t pdt2 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt2_bit; + }; + + /** + * @brief adc pdt3 register, offset:0x44 + */ + union + { + __IO uint32_t pdt3; + struct + { + __IO uint32_t pdt3 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt3_bit; + }; + + /** + * @brief adc pdt4 register, offset:0x48 + */ + union + { + __IO uint32_t pdt4; + struct + { + __IO uint32_t pdt4 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt4_bit; + }; + + /** + * @brief adc odt register, offset:0x4C + */ + union + { + __IO uint32_t odt; + struct + { + __IO uint32_t odt : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } odt_bit; + }; + + __IO uint32_t reserved1[12]; + + /** + * @brief adc ovsp register, offset:0x80 + */ + union + { + __IO uint32_t ovsp; + struct + { + __IO uint32_t oosen : 1; /* [0] */ + __IO uint32_t posen : 1; /* [1] */ + __IO uint32_t osrsel : 3; /* [4:2] */ + __IO uint32_t osssel : 4; /* [8:5] */ + __IO uint32_t oostren : 1; /* [9] */ + __IO uint32_t oosrsel : 1; /* [10] */ + __IO uint32_t reserved1 : 21; /* [31:11] */ + } ovsp_bit; + }; + + __IO uint32_t reserved2[12]; + + /** + * @brief adc calval register, offset:0xB4 + */ + union + { + __IO uint32_t calval; + struct + { + __IO uint32_t calval : 7; /* [6:0] */ + __IO uint32_t reserved1 : 25; /* [31:7] */ + } calval_bit; + }; +} adc_type; + +/** + * @brief type define adc register all + */ +typedef struct +{ + + /** + * @brief adc csts register, offset:0x00 + */ + union + { + __IO uint32_t csts; + struct + { + __IO uint32_t vmor1 : 1; /* [0] */ + __IO uint32_t occe1 : 1; /* [1] */ + __IO uint32_t pcce1 : 1; /* [2] */ + __IO uint32_t pccs1 : 1; /* [3] */ + __IO uint32_t occs1 : 1; /* [4] */ + __IO uint32_t occo1 : 1; /* [5] */ + __IO uint32_t rdy1 : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t vmor2 : 1; /* [8] */ + __IO uint32_t occe2 : 1; /* [9] */ + __IO uint32_t pcce2 : 1; /* [10] */ + __IO uint32_t pccs2 : 1; /* [11] */ + __IO uint32_t occs2 : 1; /* [12] */ + __IO uint32_t occo2 : 1; /* [13] */ + __IO uint32_t rdy2 : 1; /* [14] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t vmor3 : 1; /* [16] */ + __IO uint32_t occe3 : 1; /* [17] */ + __IO uint32_t pcce3 : 1; /* [18] */ + __IO uint32_t pccs3 : 1; /* [19] */ + __IO uint32_t occs3 : 1; /* [20] */ + __IO uint32_t occo3 : 1; /* [21] */ + __IO uint32_t rdy3 : 1; /* [22] */ + __IO uint32_t reserved3 : 9; /* [31:23] */ + } csts_bit; + }; + + /** + * @brief adc cctrl register, offset:0x04 + */ + union + { + __IO uint32_t cctrl; + struct + { + __IO uint32_t mssel : 5; /* [4_0] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t asisel : 4; /* [11:8] */ + __IO uint32_t reserved2 : 1; /* [12] */ + __IO uint32_t msdrcen : 1; /* [13] */ + __IO uint32_t msdmasel_l : 2; /* [15:14] */ + __IO uint32_t adcdiv : 4; /* [19:16] */ + __IO uint32_t reserved3 : 2; /* [21:20] */ + __IO uint32_t vbaten : 1; /* [22] */ + __IO uint32_t itsrven : 1; /* [23] */ + __IO uint32_t reserved4 : 4; /* [27:24] */ + __IO uint32_t msdmasel_h : 1; /* [28] */ + __IO uint32_t reserved5 : 3; /* [31:29] */ + } cctrl_bit; + }; + + /** + * @brief adc codt register, offset:0x08 + */ + union + { + __IO uint32_t codt; + struct + { + __IO uint32_t codtl : 16; /* [15:0] */ + __IO uint32_t codth : 16; /* [31:16] */ + } codt_bit; + }; +} adccom_type; + +/** + * @} + */ + +#define ADC1 ((adc_type *) ADC1_BASE) +#define ADC2 ((adc_type *) ADC2_BASE) +#define ADC3 ((adc_type *) ADC3_BASE) +#define ADCCOM ((adccom_type *) ADCCOM_BASE) + +/** @defgroup ADC_exported_functions + * @{ + */ + +void adc_reset(void); +void adc_enable(adc_type *adc_x, confirm_state new_state); +void adc_base_default_para_init(adc_base_config_type *adc_base_struct); +void adc_base_config(adc_type *adc_x, adc_base_config_type *adc_base_struct); +void adc_common_default_para_init(adc_common_config_type *adc_common_struct); +void adc_common_config(adc_common_config_type *adc_common_struct); +void adc_resolution_set(adc_type *adc_x, adc_resolution_type resolution); +void adc_voltage_battery_enable(confirm_state new_state); +void adc_dma_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_dma_request_repeat_enable(adc_type *adc_x, confirm_state new_state); +void adc_interrupt_enable(adc_type *adc_x, uint32_t adc_int, confirm_state new_state); +void adc_calibration_value_set(adc_type *adc_x, uint8_t adc_calibration_value); +void adc_calibration_init(adc_type *adc_x); +flag_status adc_calibration_init_status_get(adc_type *adc_x); +void adc_calibration_start(adc_type *adc_x); +flag_status adc_calibration_status_get(adc_type *adc_x); +void adc_voltage_monitor_enable(adc_type *adc_x, adc_voltage_monitoring_type adc_voltage_monitoring); +void adc_voltage_monitor_threshold_value_set(adc_type *adc_x, uint16_t adc_high_threshold, uint16_t adc_low_threshold); +void adc_voltage_monitor_single_channel_select(adc_type *adc_x, adc_channel_select_type adc_channel); +void adc_ordinary_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime); +void adc_preempt_channel_length_set(adc_type *adc_x, uint8_t adc_channel_lenght); +void adc_preempt_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime); +void adc_ordinary_conversion_trigger_set(adc_type *adc_x, adc_ordinary_trig_select_type adc_ordinary_trig, adc_ordinary_trig_edge_type adc_ordinary_trig_edge); +void adc_preempt_conversion_trigger_set(adc_type *adc_x, adc_preempt_trig_select_type adc_preempt_trig, adc_preempt_trig_edge_type adc_preempt_trig_edge); +void adc_preempt_offset_value_set(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel, uint16_t adc_offset_value); +void adc_ordinary_part_count_set(adc_type *adc_x, uint8_t adc_channel_count); +void adc_ordinary_part_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_part_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_auto_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_conversion_stop(adc_type *adc_x); +flag_status adc_conversion_stop_status_get(adc_type *adc_x); +void adc_occe_each_conversion_enable(adc_type *adc_x, confirm_state new_state); +void adc_ordinary_software_trigger_enable(adc_type *adc_x, confirm_state new_state); +flag_status adc_ordinary_software_trigger_status_get(adc_type *adc_x); +void adc_preempt_software_trigger_enable(adc_type *adc_x, confirm_state new_state); +flag_status adc_preempt_software_trigger_status_get(adc_type *adc_x); +uint16_t adc_ordinary_conversion_data_get(adc_type *adc_x); +uint32_t adc_combine_ordinary_conversion_data_get(void); +uint16_t adc_preempt_conversion_data_get(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel); +flag_status adc_flag_get(adc_type *adc_x, uint8_t adc_flag); +void adc_flag_clear(adc_type *adc_x, uint32_t adc_flag); +void adc_ordinary_oversample_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_oversample_enable(adc_type *adc_x, confirm_state new_state); +void adc_oversample_ratio_shift_set(adc_type *adc_x, adc_oversample_ratio_type adc_oversample_ratio, adc_oversample_shift_type adc_oversample_shift); +void adc_ordinary_oversample_trig_enable(adc_type *adc_x, confirm_state new_state); +void adc_ordinary_oversample_restart_set(adc_type *adc_x, adc_ordinary_oversample_restart_type adc_ordinary_oversample_restart); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h new file mode 100644 index 0000000000..ddb1a07402 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h @@ -0,0 +1,1042 @@ +/** + ************************************************************************** + * @file at32f435_437_can.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 can header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CAN_H +#define __AT32F435_437_CAN_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + + +/** @defgroup CAN_timeout_count + * @{ + */ + +#define FZC_TIMEOUT ((uint32_t)0x0000FFFF) /*!< time out for fzc bit */ +#define DZC_TIMEOUT ((uint32_t)0x0000FFFF) /*!< time out for dzc bit */ + +/** + * @} + */ + +/** @defgroup CAN_flags_definition + * @brief can flag + * @{ + */ + +#define CAN_EAF_FLAG ((uint32_t)0x01) /*!< error active flag */ +#define CAN_EPF_FLAG ((uint32_t)0x02) /*!< error passive flag */ +#define CAN_BOF_FLAG ((uint32_t)0x03) /*!< bus-off flag */ +#define CAN_ETR_FLAG ((uint32_t)0x04) /*!< error type record flag */ +#define CAN_EOIF_FLAG ((uint32_t)0x05) /*!< error occur interrupt flag */ +#define CAN_TM0TCF_FLAG ((uint32_t)0x06) /*!< transmit mailbox 0 transmission completed flag */ +#define CAN_TM1TCF_FLAG ((uint32_t)0x07) /*!< transmit mailbox 1 transmission completed flag */ +#define CAN_TM2TCF_FLAG ((uint32_t)0x08) /*!< transmit mailbox 2 transmission completed flag */ +#define CAN_RF0MN_FLAG ((uint32_t)0x09) /*!< receive fifo 0 message num flag */ +#define CAN_RF0FF_FLAG ((uint32_t)0x0A) /*!< receive fifo 0 full flag */ +#define CAN_RF0OF_FLAG ((uint32_t)0x0B) /*!< receive fifo 0 overflow flag */ +#define CAN_RF1MN_FLAG ((uint32_t)0x0C) /*!< receive fifo 1 message num flag */ +#define CAN_RF1FF_FLAG ((uint32_t)0x0D) /*!< receive fifo 1 full flag */ +#define CAN_RF1OF_FLAG ((uint32_t)0x0E) /*!< receive fifo 1 overflow flag */ +#define CAN_QDZIF_FLAG ((uint32_t)0x0F) /*!< quit doze mode interrupt flag */ +#define CAN_EDZC_FLAG ((uint32_t)0x10) /*!< enter doze mode confirm flag */ +#define CAN_TMEF_FLAG ((uint32_t)0x11) /*!< transmit mailbox empty flag */ + +/** + * @} + */ + +/** @defgroup CAN_interrupts_definition + * @brief can interrupt + * @{ + */ + +#define CAN_TCIEN_INT ((uint32_t)0x00000001) /*!< transmission complete interrupt */ +#define CAN_RF0MIEN_INT ((uint32_t)0x00000002) /*!< receive fifo 0 message interrupt */ +#define CAN_RF0FIEN_INT ((uint32_t)0x00000004) /*!< receive fifo 0 full interrupt */ +#define CAN_RF0OIEN_INT ((uint32_t)0x00000008) /*!< receive fifo 0 overflow interrupt */ +#define CAN_RF1MIEN_INT ((uint32_t)0x00000010) /*!< receive fifo 1 message interrupt */ +#define CAN_RF1FIEN_INT ((uint32_t)0x00000020) /*!< receive fifo 1 full interrupt */ +#define CAN_RF1OIEN_INT ((uint32_t)0x00000040) /*!< receive fifo 1 overflow interrupt */ +#define CAN_EAIEN_INT ((uint32_t)0x00000100) /*!< error active interrupt */ +#define CAN_EPIEN_INT ((uint32_t)0x00000200) /*!< error passive interrupt */ +#define CAN_BOIEN_INT ((uint32_t)0x00000400) /*!< bus-off interrupt */ +#define CAN_ETRIEN_INT ((uint32_t)0x00000800) /*!< error type record interrupt */ +#define CAN_EOIEN_INT ((uint32_t)0x00008000) /*!< error occur interrupt */ +#define CAN_QDZIEN_INT ((uint32_t)0x00010000) /*!< quit doze mode interrupt */ +#define CAN_EDZIEN_INT ((uint32_t)0x00020000) /*!< enter doze mode confirm interrupt */ + +/** + * @} + */ + +/** + * @brief can flag clear operation macro definition val + */ +#define CAN_MSTS_EOIF_VAL ((uint32_t)0x00000004) /*!< eoif bit value, it clear by writing 1 */ +#define CAN_MSTS_QDZIF_VAL ((uint32_t)0x00000008) /*!< qdzif bit value, it clear by writing 1 */ +#define CAN_MSTS_EDZIF_VAL ((uint32_t)0x00000010) /*!< edzif bit value, it clear by writing 1 */ +#define CAN_TSTS_TM0TCF_VAL ((uint32_t)0x00000001) /*!< tm0tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM1TCF_VAL ((uint32_t)0x00000100) /*!< tm1tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM2TCF_VAL ((uint32_t)0x00010000) /*!< tm2tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM0CT_VAL ((uint32_t)0x00000080) /*!< tm0ct bit value, it clear by writing 1 */ +#define CAN_TSTS_TM1CT_VAL ((uint32_t)0x00008000) /*!< tm1ct bit value, it clear by writing 1 */ +#define CAN_TSTS_TM2CT_VAL ((uint32_t)0x00800000) /*!< tm2ct bit value, it clear by writing 1 */ +#define CAN_RF0_RF0FF_VAL ((uint32_t)0x00000008) /*!< rf0ff bit value, it clear by writing 1 */ +#define CAN_RF0_RF0OF_VAL ((uint32_t)0x00000010) /*!< rf0of bit value, it clear by writing 1 */ +#define CAN_RF0_RF0R_VAL ((uint32_t)0x00000020) /*!< rf0r bit value, it clear by writing 1 */ +#define CAN_RF1_RF1FF_VAL ((uint32_t)0x00000008) /*!< rf1ff bit value, it clear by writing 1 */ +#define CAN_RF1_RF1OF_VAL ((uint32_t)0x00000010) /*!< rf1of bit value, it clear by writing 1 */ +#define CAN_RF1_RF1R_VAL ((uint32_t)0x00000020) /*!< rf1r bit value, it clear by writing 1 */ + +/** @defgroup CAN_exported_types + * @{ + */ + +/** + * @brief can filter fifo + */ +typedef enum +{ + CAN_FILTER_FIFO0 = 0x00, /*!< filter fifo 0 assignment for filter x */ + CAN_FILTER_FIFO1 = 0x01 /*!< filter fifo 1 assignment for filter x */ +} can_filter_fifo_type; + +/** + * @brief can filter mode + */ +typedef enum +{ + CAN_FILTER_MODE_ID_MASK = 0x00, /*!< identifier mask mode */ + CAN_FILTER_MODE_ID_LIST = 0x01 /*!< identifier list mode */ +} can_filter_mode_type; + +/** + * @brief can filter bit width select + */ +typedef enum +{ + CAN_FILTER_16BIT = 0x00, /*!< two 16-bit filters */ + CAN_FILTER_32BIT = 0x01 /*!< one 32-bit filter */ +} can_filter_bit_width_type; + +/** + * @brief can mode + */ +typedef enum +{ + CAN_MODE_COMMUNICATE = 0x00, /*!< communication mode */ + CAN_MODE_LOOPBACK = 0x01, /*!< loopback mode */ + CAN_MODE_LISTENONLY = 0x02, /*!< listen-only mode */ + CAN_MODE_LISTENONLY_LOOPBACK = 0x03 /*!< loopback combined with listen-only mode */ +} can_mode_type; + +/** + * @brief can operating mode + */ +typedef enum +{ + CAN_OPERATINGMODE_FREEZE = 0x00, /*!< freeze mode */ + CAN_OPERATINGMODE_DOZE = 0x01, /*!< doze mode */ + CAN_OPERATINGMODE_COMMUNICATE = 0x02 /*!< communication mode */ +} can_operating_mode_type; + +/** + * @brief can resynchronization adjust width + */ +typedef enum +{ + CAN_RSAW_1TQ = 0x00, /*!< 1 time quantum */ + CAN_RSAW_2TQ = 0x01, /*!< 2 time quantum */ + CAN_RSAW_3TQ = 0x02, /*!< 3 time quantum */ + CAN_RSAW_4TQ = 0x03 /*!< 4 time quantum */ +} can_rsaw_type; + +/** + * @brief can bit time segment 1 + */ +typedef enum +{ + CAN_BTS1_1TQ = 0x00, /*!< 1 time quantum */ + CAN_BTS1_2TQ = 0x01, /*!< 2 time quantum */ + CAN_BTS1_3TQ = 0x02, /*!< 3 time quantum */ + CAN_BTS1_4TQ = 0x03, /*!< 4 time quantum */ + CAN_BTS1_5TQ = 0x04, /*!< 5 time quantum */ + CAN_BTS1_6TQ = 0x05, /*!< 6 time quantum */ + CAN_BTS1_7TQ = 0x06, /*!< 7 time quantum */ + CAN_BTS1_8TQ = 0x07, /*!< 8 time quantum */ + CAN_BTS1_9TQ = 0x08, /*!< 9 time quantum */ + CAN_BTS1_10TQ = 0x09, /*!< 10 time quantum */ + CAN_BTS1_11TQ = 0x0A, /*!< 11 time quantum */ + CAN_BTS1_12TQ = 0x0B, /*!< 12 time quantum */ + CAN_BTS1_13TQ = 0x0C, /*!< 13 time quantum */ + CAN_BTS1_14TQ = 0x0D, /*!< 14 time quantum */ + CAN_BTS1_15TQ = 0x0E, /*!< 15 time quantum */ + CAN_BTS1_16TQ = 0x0F /*!< 16 time quantum */ +} can_bts1_type; + +/** + * @brief can bit time segment 2 + */ +typedef enum +{ + CAN_BTS2_1TQ = 0x00, /*!< 1 time quantum */ + CAN_BTS2_2TQ = 0x01, /*!< 2 time quantum */ + CAN_BTS2_3TQ = 0x02, /*!< 3 time quantum */ + CAN_BTS2_4TQ = 0x03, /*!< 4 time quantum */ + CAN_BTS2_5TQ = 0x04, /*!< 5 time quantum */ + CAN_BTS2_6TQ = 0x05, /*!< 6 time quantum */ + CAN_BTS2_7TQ = 0x06, /*!< 7 time quantum */ + CAN_BTS2_8TQ = 0x07 /*!< 8 time quantum */ +} can_bts2_type; + +/** + * @brief can identifier type + */ +typedef enum +{ + CAN_ID_STANDARD = 0x00, /*!< standard Id */ + CAN_ID_EXTENDED = 0x01 /*!< extended Id */ +} can_identifier_type; + +/** + * @brief can transmission frame type + */ +typedef enum +{ + CAN_TFT_DATA = 0x00, /*!< data frame */ + CAN_TFT_REMOTE = 0x01 /*!< remote frame */ +} can_trans_frame_type; + +/** + * @brief can tx mailboxes + */ +typedef enum +{ + CAN_TX_MAILBOX0 = 0x00, /*!< can tx mailbox 0 */ + CAN_TX_MAILBOX1 = 0x01, /*!< can tx mailbox 1 */ + CAN_TX_MAILBOX2 = 0x02 /*!< can tx mailbox 2 */ +} can_tx_mailbox_num_type; + +/** + * @brief can receive fifo + */ +typedef enum +{ + CAN_RX_FIFO0 = 0x00, /*!< can fifo 0 used to receive */ + CAN_RX_FIFO1 = 0x01 /*!< can fifo 1 used to receive */ +} can_rx_fifo_num_type; + +/** + * @brief can transmit status + */ +typedef enum +{ + CAN_TX_STATUS_FAILED = 0x00, /*!< can transmission failed */ + CAN_TX_STATUS_SUCCESSFUL = 0x01, /*!< can transmission successful */ + CAN_TX_STATUS_PENDING = 0x02, /*!< can transmission pending */ + CAN_TX_STATUS_NO_EMPTY = 0x04 /*!< can transmission no empty mailbox */ +} can_transmit_status_type; + +/** + * @brief can enter doze mode status + */ +typedef enum +{ + CAN_ENTER_DOZE_FAILED = 0x00, /*!< can enter the doze mode failed */ + CAN_ENTER_DOZE_SUCCESSFUL = 0x01 /*!< can enter the doze mode successful */ +} can_enter_doze_status_type; + +/** + * @brief can quit doze mode status + */ +typedef enum +{ + CAN_QUIT_DOZE_FAILED = 0x00, /*!< can quit doze mode failed */ + CAN_QUIT_DOZE_SUCCESSFUL = 0x01 /*!< can quit doze mode successful */ +} can_quit_doze_status_type; + +/** + * @brief can message discarding rule select when overflow + */ +typedef enum +{ + CAN_DISCARDING_FIRST_RECEIVED = 0x00, /*!< can discarding the first received message */ + CAN_DISCARDING_LAST_RECEIVED = 0x01 /*!< can discarding the last received message */ +} can_msg_discarding_rule_type; + +/** + * @brief can multiple message sending sequence rule + */ +typedef enum +{ + CAN_SENDING_BY_ID = 0x00, /*!< can sending the minimum id message first*/ + CAN_SENDING_BY_REQUEST = 0x01 /*!< can sending the first request message first */ +} can_msg_sending_rule_type; + +/** + * @brief can error type record + */ +typedef enum +{ + CAN_ERRORRECORD_NOERR = 0x00, /*!< no error */ + CAN_ERRORRECORD_STUFFERR = 0x01, /*!< stuff error */ + CAN_ERRORRECORD_FORMERR = 0x02, /*!< form error */ + CAN_ERRORRECORD_ACKERR = 0x03, /*!< acknowledgment error */ + CAN_ERRORRECORD_BITRECESSIVEERR = 0x04, /*!< bit recessive error */ + CAN_ERRORRECORD_BITDOMINANTERR = 0x05, /*!< bit dominant error */ + CAN_ERRORRECORD_CRCERR = 0x06, /*!< crc error */ + CAN_ERRORRECORD_SOFTWARESETERR = 0x07 /*!< software set error */ +} can_error_record_type; + +/** + * @brief can init structure definition + */ +typedef struct +{ + can_mode_type mode_selection; /*!< specifies the can mode.*/ + + confirm_state ttc_enable; /*!< time triggered communication mode enable */ + + confirm_state aebo_enable; /*!< automatic exit bus-off enable */ + + confirm_state aed_enable; /*!< automatic exit doze mode enable */ + + confirm_state prsf_enable; /*!< prohibit retransmission when sending fails enable */ + + can_msg_discarding_rule_type mdrsel_selection; /*!< message discarding rule select when overflow */ + + can_msg_sending_rule_type mmssr_selection; /*!< multiple message sending sequence rule */ + +} can_base_type; + +/** + * @brief can baudrate structure definition + */ +typedef struct +{ + uint16_t baudrate_div; /*!< baudrate division,this parameter can be 0x001~0x1000.*/ + + can_rsaw_type rsaw_size; /*!< resynchronization adjust width */ + + can_bts1_type bts1_size; /*!< bit time segment 1 */ + + can_bts2_type bts2_size; /*!< bit time segment 2 */ + +} can_baudrate_type; + +/** + * @brief can filter init structure definition + */ +typedef struct +{ + confirm_state filter_activate_enable; /*!< enable or disable the filter activate.*/ + + can_filter_mode_type filter_mode; /*!< config the filter mode mask or list.*/ + + can_filter_fifo_type filter_fifo; /*!< config the fifo which will be assigned to the filter. */ + + uint8_t filter_number; /*!< config the filter number, parameter ranges from 0 to 13. */ + + can_filter_bit_width_type filter_bit; /*!< config the filter bit width 16bit or 32bit.*/ + + uint16_t filter_id_high; /*!< config the filter identification, for 32-bit configuration + it's high 16 bits, for 16-bit configuration it's first. */ + + uint16_t filter_id_low; /*!< config the filter identification, for 32-bit configuration + it's low 16 bits, for 16-bit configuration it's second. */ + + uint16_t filter_mask_high; /*!< config the filter mask or identification, according to the filtering mode, + for 32-bit configuration it's high 16 bits, for 16-bit configuration it's first. */ + + uint16_t filter_mask_low; /*!< config the filter mask or identification, according to the filtering mode, + for 32-bit configuration it's low 16 bits, for 16-bit configuration it's second. */ +} can_filter_init_type; + +/** + * @brief can tx message structure definition + */ +typedef struct +{ + uint32_t standard_id; /*!< specifies the 11 bits standard identifier. + this parameter can be a value between 0 to 0x7FF. */ + + uint32_t extended_id; /*!< specifies the 29 bits extended identifier. + this parameter can be a value between 0 to 0x1FFFFFFF. */ + + can_identifier_type id_type; /*!< specifies identifier type for the transmit message.*/ + + can_trans_frame_type frame_type; /*!< specifies frame type for the transmit message.*/ + + uint8_t dlc; /*!< specifies frame data length that will be transmitted. + this parameter can be a value between 0 to 8 */ + + uint8_t data[8]; /*!< contains the transmit data. it ranges from 0 to 0xFF. */ + +} can_tx_message_type; + +/** + * @brief can rx message structure definition + */ +typedef struct +{ + uint32_t standard_id; /*!< specifies the 11 bits standard identifier + this parameter can be a value between 0 to 0x7FF. */ + + uint32_t extended_id; /*!< specifies the 29 bits extended identifier. + this parameter can be a value between 0 to 0x1FFFFFFF. */ + + can_identifier_type id_type; /*!< specifies identifier type for the receive message.*/ + + can_trans_frame_type frame_type; /*!< specifies frame type for the receive message.*/ + + uint8_t dlc; /*!< specifies the frame data length that will be received. + this parameter can be a value between 0 to 8 */ + + uint8_t data[8]; /*!< contains the receive data. it ranges from 0 to 0xFF.*/ + + uint8_t filter_index; /*!< specifies the message stored in which filter + this parameter can be a value between 0 to 0xFF */ +} can_rx_message_type; + +/** + * @brief can controller area network tx mailbox + */ +typedef struct +{ + /** + * @brief can tmi register + */ + union + { + __IO uint32_t tmi; + struct + { + __IO uint32_t tmsr : 1; /* [0] */ + __IO uint32_t tmfrsel : 1; /* [1] */ + __IO uint32_t tmidsel : 1; /* [2] */ + __IO uint32_t tmeid : 18;/* [20:3] */ + __IO uint32_t tmsid : 11;/* [31:21] */ + } tmi_bit; + }; + + /** + * @brief can tmc register + */ + union + { + __IO uint32_t tmc; + struct + { + __IO uint32_t tmdtbl : 4; /* [3:0] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t tmtsten : 1; /* [8] */ + __IO uint32_t reserved2 : 7; /* [15:9] */ + __IO uint32_t tmts : 16;/* [31:16] */ + } tmc_bit; + }; + + /** + * @brief can tmdtl register + */ + union + { + __IO uint32_t tmdtl; + struct + { + __IO uint32_t tmdt0 : 8; /* [7:0] */ + __IO uint32_t tmdt1 : 8; /* [15:8] */ + __IO uint32_t tmdt2 : 8; /* [23:16] */ + __IO uint32_t tmdt3 : 8; /* [31:24] */ + } tmdtl_bit; + }; + + /** + * @brief can tmdth register + */ + union + { + __IO uint32_t tmdth; + struct + { + __IO uint32_t tmdt4 : 8; /* [7:0] */ + __IO uint32_t tmdt5 : 8; /* [15:8] */ + __IO uint32_t tmdt6 : 8; /* [23:16] */ + __IO uint32_t tmdt7 : 8; /* [31:24] */ + } tmdth_bit; + }; +} can_tx_mailbox_type; + +/** + * @brief can controller area network fifo mailbox + */ +typedef struct +{ + /** + * @brief can rfi register + */ + union + { + __IO uint32_t rfi; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t rffri : 1; /* [1] */ + __IO uint32_t rfidi : 1; /* [2] */ + __IO uint32_t rfeid : 18;/* [20:3] */ + __IO uint32_t rfsid : 11;/* [31:21] */ + } rfi_bit; + }; + + /** + * @brief can rfc register + */ + union + { + __IO uint32_t rfc; + struct + { + __IO uint32_t rfdtl : 4; /* [3:0] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t rffmn : 8; /* [15:8] */ + __IO uint32_t rfts : 16;/* [31:16] */ + } rfc_bit; + }; + + /** + * @brief can rfdtl register + */ + union + { + __IO uint32_t rfdtl; + struct + { + __IO uint32_t rfdt0 : 8; /* [7:0] */ + __IO uint32_t rfdt1 : 8; /* [15:8] */ + __IO uint32_t rfdt2 : 8; /* [23:16] */ + __IO uint32_t rfdt3 : 8; /* [31:24] */ + } rfdtl_bit; + }; + + /** + * @brief can rfdth register + */ + union + { + __IO uint32_t rfdth; + struct + { + __IO uint32_t rfdt4 : 8; /* [7:0] */ + __IO uint32_t rfdt5 : 8; /* [15:8] */ + __IO uint32_t rfdt6 : 8; /* [23:16] */ + __IO uint32_t rfdt7 : 8; /* [31:24] */ + } rfdth_bit; + }; +} can_fifo_mailbox_type; + +/** + * @brief can controller area network filter bit register + */ +typedef struct +{ + __IO uint32_t ffdb1; + __IO uint32_t ffdb2; +} can_filter_register_type; + +/** + * @brief type define can register all + */ +typedef struct +{ + + /** + * @brief can mctrl register, offset:0x00 + */ + union + { + __IO uint32_t mctrl; + struct + { + __IO uint32_t fzen : 1; /* [0] */ + __IO uint32_t dzen : 1; /* [1] */ + __IO uint32_t mmssr : 1; /* [2] */ + __IO uint32_t mdrsel : 1; /* [3] */ + __IO uint32_t prsfen : 1; /* [4] */ + __IO uint32_t aeden : 1; /* [5] */ + __IO uint32_t aeboen : 1; /* [6] */ + __IO uint32_t ttcen : 1; /* [7] */ + __IO uint32_t reserved1 : 7; /* [14:8] */ + __IO uint32_t sprst : 1; /* [15] */ + __IO uint32_t ptd : 1; /* [16] */ + __IO uint32_t reserved2 : 15;/*[31:17] */ + } mctrl_bit; + }; + + /** + * @brief can msts register, offset:0x04 + */ + union + { + __IO uint32_t msts; + struct + { + __IO uint32_t fzc : 1; /* [0] */ + __IO uint32_t dzc : 1; /* [1] */ + __IO uint32_t eoif : 1; /* [2] */ + __IO uint32_t qdzif : 1; /* [3] */ + __IO uint32_t edzif : 1; /* [4] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t cuss : 1; /* [8] */ + __IO uint32_t curs : 1; /* [9] */ + __IO uint32_t lsamprx : 1; /* [10] */ + __IO uint32_t realrx : 1; /* [11] */ + __IO uint32_t reserved2 : 20;/*[31:12] */ + } msts_bit; + }; + + /** + * @brief can tsts register, offset:0x08 + */ + union + { + __IO uint32_t tsts; + struct + { + __IO uint32_t tm0tcf : 1; /* [0] */ + __IO uint32_t tm0tsf : 1; /* [1] */ + __IO uint32_t tm0alf : 1; /* [2] */ + __IO uint32_t tm0tef : 1; /* [3] */ + __IO uint32_t reserved1 : 3; /* [6:4] */ + __IO uint32_t tm0ct : 1; /* [7] */ + __IO uint32_t tm1tcf : 1; /* [8] */ + __IO uint32_t tm1tsf : 1; /* [9] */ + __IO uint32_t tm1alf : 1; /* [10] */ + __IO uint32_t tm1tef : 1; /* [11] */ + __IO uint32_t reserved2 : 3; /* [14:12] */ + __IO uint32_t tm1ct : 1; /* [15] */ + __IO uint32_t tm2tcf : 1; /* [16] */ + __IO uint32_t tm2tsf : 1; /* [17] */ + __IO uint32_t tm2alf : 1; /* [18] */ + __IO uint32_t tm2tef : 1; /* [19] */ + __IO uint32_t reserved3 : 3; /* [22:20] */ + __IO uint32_t tm2ct : 1; /* [23] */ + __IO uint32_t tmnr : 2; /* [25:24] */ + __IO uint32_t tm0ef : 1; /* [26] */ + __IO uint32_t tm1ef : 1; /* [27] */ + __IO uint32_t tm2ef : 1; /* [28] */ + __IO uint32_t tm0lpf : 1; /* [29] */ + __IO uint32_t tm1lpf : 1; /* [30] */ + __IO uint32_t tm2lpf : 1; /* [31] */ + } tsts_bit; + }; + + /** + * @brief can rf0 register, offset:0x0C + */ + union + { + __IO uint32_t rf0; + struct + { + __IO uint32_t rf0mn : 2; /* [1:0] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t rf0ff : 1; /* [3] */ + __IO uint32_t rf0of : 1; /* [4] */ + __IO uint32_t rf0r : 1; /* [5] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } rf0_bit; + }; + + /** + * @brief can rf1 register, offset:0x10 + */ + union + { + __IO uint32_t rf1; + struct + { + __IO uint32_t rf1mn : 2; /* [1:0] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t rf1ff : 1; /* [3] */ + __IO uint32_t rf1of : 1; /* [4] */ + __IO uint32_t rf1r : 1; /* [5] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } rf1_bit; + }; + + /** + * @brief can inten register, offset:0x14 + */ + union + { + __IO uint32_t inten; + struct + { + __IO uint32_t tcien : 1; /* [0] */ + __IO uint32_t rf0mien : 1; /* [1] */ + __IO uint32_t rf0fien : 1; /* [2] */ + __IO uint32_t rf0oien : 1; /* [3] */ + __IO uint32_t rf1mien : 1; /* [4] */ + __IO uint32_t rf1fien : 1; /* [5] */ + __IO uint32_t rf1oien : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t eaien : 1; /* [8] */ + __IO uint32_t epien : 1; /* [9] */ + __IO uint32_t boien : 1; /* [10] */ + __IO uint32_t etrien : 1; /* [11] */ + __IO uint32_t reserved2 : 3; /* [14:12] */ + __IO uint32_t eoien : 1; /* [15] */ + __IO uint32_t qdzien : 1; /* [16] */ + __IO uint32_t edzien : 1; /* [17] */ + __IO uint32_t reserved3 : 14;/* [31:18] */ + } inten_bit; + }; + + /** + * @brief can ests register, offset:0x18 + */ + union + { + __IO uint32_t ests; + struct + { + __IO uint32_t eaf : 1; /* [0] */ + __IO uint32_t epf : 1; /* [1] */ + __IO uint32_t bof : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t etr : 3; /* [6:4] */ + __IO uint32_t reserved2 : 9; /* [15:7] */ + __IO uint32_t tec : 8; /* [23:16] */ + __IO uint32_t rec : 8; /* [31:24] */ + } ests_bit; + }; + + /** + * @brief can btmg register, offset:0x1C + */ + union + { + __IO uint32_t btmg; + struct + { + __IO uint32_t brdiv : 12;/* [11:0] */ + __IO uint32_t reserved1 : 4; /* [15:12] */ + __IO uint32_t bts1 : 4; /* [19:16] */ + __IO uint32_t bts2 : 3; /* [22:20] */ + __IO uint32_t reserved2 : 1; /* [23] */ + __IO uint32_t rsaw : 2; /* [25:24] */ + __IO uint32_t reserved3 : 4; /* [29:26] */ + __IO uint32_t lben : 1; /* [30] */ + __IO uint32_t loen : 1; /* [31] */ + } btmg_bit; + }; + + /** + * @brief can reserved register, offset:0x20~0x17C + */ + __IO uint32_t reserved1[88]; + + /** + * @brief can controller area network tx mailbox register, offset:0x180~0x1AC + */ + can_tx_mailbox_type tx_mailbox[3]; + + /** + * @brief can controller area network fifo mailbox register, offset:0x1B0~0x1CC + */ + can_fifo_mailbox_type fifo_mailbox[2]; + + /** + * @brief can reserved register, offset:0x1D0~0x1FC + */ + __IO uint32_t reserved2[12]; + + /** + * @brief can fctrl register, offset:0x200 + */ + union + { + __IO uint32_t fctrl; + struct + { + __IO uint32_t fcs : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } fctrl_bit; + }; + + /** + * @brief can fmcfg register, offset:0x204 + */ + union + { + __IO uint32_t fmcfg; + struct + { + __IO uint32_t fmsel0 : 1; /* [0] */ + __IO uint32_t fmsel1 : 1; /* [1] */ + __IO uint32_t fmsel2 : 1; /* [2] */ + __IO uint32_t fmsel3 : 1; /* [3] */ + __IO uint32_t fmsel4 : 1; /* [4] */ + __IO uint32_t fmsel5 : 1; /* [5] */ + __IO uint32_t fmsel6 : 1; /* [6] */ + __IO uint32_t fmsel7 : 1; /* [7] */ + __IO uint32_t fmsel8 : 1; /* [8] */ + __IO uint32_t fmsel9 : 1; /* [9] */ + __IO uint32_t fmsel10 : 1; /* [10] */ + __IO uint32_t fmsel11 : 1; /* [11] */ + __IO uint32_t fmsel12 : 1; /* [12] */ + __IO uint32_t fmsel13 : 1; /* [13] */ + __IO uint32_t fmsel14 : 1; /* [14] */ + __IO uint32_t fmsel15 : 1; /* [15] */ + __IO uint32_t fmsel16 : 1; /* [16] */ + __IO uint32_t fmsel17 : 1; /* [17] */ + __IO uint32_t fmsel18 : 1; /* [18] */ + __IO uint32_t fmsel19 : 1; /* [19] */ + __IO uint32_t fmsel20 : 1; /* [20] */ + __IO uint32_t fmsel21 : 1; /* [21] */ + __IO uint32_t fmsel22 : 1; /* [22] */ + __IO uint32_t fmsel23 : 1; /* [23] */ + __IO uint32_t fmsel24 : 1; /* [24] */ + __IO uint32_t fmsel25 : 1; /* [25] */ + __IO uint32_t fmsel26 : 1; /* [26] */ + __IO uint32_t fmsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } fmcfg_bit; + }; + + /** + * @brief can reserved register, offset:0x208 + */ + __IO uint32_t reserved3; + + /** + * @brief can fbwcfg register, offset:0x20C + */ + union + { + __IO uint32_t fbwcfg; + struct + { + __IO uint32_t fbwsel0 : 1; /* [0] */ + __IO uint32_t fbwsel1 : 1; /* [1] */ + __IO uint32_t fbwsel2 : 1; /* [2] */ + __IO uint32_t fbwsel3 : 1; /* [3] */ + __IO uint32_t fbwsel4 : 1; /* [4] */ + __IO uint32_t fbwsel5 : 1; /* [5] */ + __IO uint32_t fbwsel6 : 1; /* [6] */ + __IO uint32_t fbwsel7 : 1; /* [7] */ + __IO uint32_t fbwsel8 : 1; /* [8] */ + __IO uint32_t fbwsel9 : 1; /* [9] */ + __IO uint32_t fbwsel10 : 1; /* [10] */ + __IO uint32_t fbwsel11 : 1; /* [11] */ + __IO uint32_t fbwsel12 : 1; /* [12] */ + __IO uint32_t fbwsel13 : 1; /* [13] */ + __IO uint32_t fbwsel14 : 1; /* [14] */ + __IO uint32_t fbwsel15 : 1; /* [15] */ + __IO uint32_t fbwsel16 : 1; /* [16] */ + __IO uint32_t fbwsel17 : 1; /* [17] */ + __IO uint32_t fbwsel18 : 1; /* [18] */ + __IO uint32_t fbwsel19 : 1; /* [19] */ + __IO uint32_t fbwsel20 : 1; /* [20] */ + __IO uint32_t fbwsel21 : 1; /* [21] */ + __IO uint32_t fbwsel22 : 1; /* [22] */ + __IO uint32_t fbwsel23 : 1; /* [23] */ + __IO uint32_t fbwsel24 : 1; /* [24] */ + __IO uint32_t fbwsel25 : 1; /* [25] */ + __IO uint32_t fbwsel26 : 1; /* [26] */ + __IO uint32_t fbwsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } fbwcfg_bit; + }; + + /** + * @brief can reserved register, offset:0x210 + */ + __IO uint32_t reserved4; + + /** + * @brief can frf register, offset:0x214 + */ + union + { + __IO uint32_t frf; + struct + { + __IO uint32_t frfsel0 : 1; /* [0] */ + __IO uint32_t frfsel1 : 1; /* [1] */ + __IO uint32_t frfsel2 : 1; /* [2] */ + __IO uint32_t frfsel3 : 1; /* [3] */ + __IO uint32_t frfsel4 : 1; /* [4] */ + __IO uint32_t frfsel5 : 1; /* [5] */ + __IO uint32_t frfsel6 : 1; /* [6] */ + __IO uint32_t frfsel7 : 1; /* [7] */ + __IO uint32_t frfsel8 : 1; /* [8] */ + __IO uint32_t frfsel9 : 1; /* [9] */ + __IO uint32_t frfsel10 : 1; /* [10] */ + __IO uint32_t frfsel11 : 1; /* [11] */ + __IO uint32_t frfsel12 : 1; /* [12] */ + __IO uint32_t frfsel13 : 1; /* [13] */ + __IO uint32_t frfsel14 : 1; /* [14] */ + __IO uint32_t frfsel15 : 1; /* [15] */ + __IO uint32_t frfsel16 : 1; /* [16] */ + __IO uint32_t frfsel17 : 1; /* [17] */ + __IO uint32_t frfsel18 : 1; /* [18] */ + __IO uint32_t frfsel19 : 1; /* [19] */ + __IO uint32_t frfsel20 : 1; /* [20] */ + __IO uint32_t frfsel21 : 1; /* [21] */ + __IO uint32_t frfsel22 : 1; /* [22] */ + __IO uint32_t frfsel23 : 1; /* [23] */ + __IO uint32_t frfsel24 : 1; /* [24] */ + __IO uint32_t frfsel25 : 1; /* [25] */ + __IO uint32_t frfsel26 : 1; /* [26] */ + __IO uint32_t frfsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } frf_bit; + }; + + /** + * @brief can reserved register, offset:0x218 + */ + __IO uint32_t reserved5; + + /** + * @brief can facfg register, offset:0x21C + */ + union + { + __IO uint32_t facfg; + struct + { + __IO uint32_t faen0 : 1; /* [0] */ + __IO uint32_t faen1 : 1; /* [1] */ + __IO uint32_t faen2 : 1; /* [2] */ + __IO uint32_t faen3 : 1; /* [3] */ + __IO uint32_t faen4 : 1; /* [4] */ + __IO uint32_t faen5 : 1; /* [5] */ + __IO uint32_t faen6 : 1; /* [6] */ + __IO uint32_t faen7 : 1; /* [7] */ + __IO uint32_t faen8 : 1; /* [8] */ + __IO uint32_t faen9 : 1; /* [9] */ + __IO uint32_t faen10 : 1; /* [10] */ + __IO uint32_t faen11 : 1; /* [11] */ + __IO uint32_t faen12 : 1; /* [12] */ + __IO uint32_t faen13 : 1; /* [13] */ + __IO uint32_t faen14 : 1; /* [14] */ + __IO uint32_t faen15 : 1; /* [15] */ + __IO uint32_t faen16 : 1; /* [16] */ + __IO uint32_t faen17 : 1; /* [17] */ + __IO uint32_t faen18 : 1; /* [18] */ + __IO uint32_t faen19 : 1; /* [19] */ + __IO uint32_t faen20 : 1; /* [20] */ + __IO uint32_t faen21 : 1; /* [21] */ + __IO uint32_t faen22 : 1; /* [22] */ + __IO uint32_t faen23 : 1; /* [23] */ + __IO uint32_t faen24 : 1; /* [24] */ + __IO uint32_t faen25 : 1; /* [25] */ + __IO uint32_t faen26 : 1; /* [26] */ + __IO uint32_t faen27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } facfg_bit; + }; + + /** + * @brief can reserved register, offset:0x220~0x23C + */ + __IO uint32_t reserved6[8]; + + /** + * @brief can ffb register, offset:0x240~0x2AC + */ + can_filter_register_type ffb[28]; +} can_type; + +/** + * @} + */ + +#define CAN1 ((can_type *) CAN1_BASE) +#define CAN2 ((can_type *) CAN2_BASE) + +/** @defgroup CAN_exported_functions + * @{ + */ + +void can_reset(can_type* can_x); +void can_baudrate_default_para_init(can_baudrate_type* can_baudrate_struct); +error_status can_baudrate_set(can_type* can_x, can_baudrate_type* can_baudrate_struct); +void can_default_para_init(can_base_type* can_base_struct); +error_status can_base_init(can_type* can_x, can_base_type* can_base_struct); +void can_filter_default_para_init(can_filter_init_type* can_filter_init_struct); +void can_filter_init(can_type* can_x, can_filter_init_type* can_filter_init_struct); +void can_debug_transmission_prohibit(can_type* can_x, confirm_state new_state); +void can_ttc_mode_enable(can_type* can_x, confirm_state new_state); +uint8_t can_message_transmit(can_type* can_x, can_tx_message_type* tx_message_struct); +can_transmit_status_type can_transmit_status_get(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox); +void can_transmit_cancel(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox); +void can_message_receive(can_type* can_x, can_rx_fifo_num_type fifo_number, can_rx_message_type* rx_message_struct); +void can_receive_fifo_release(can_type* can_x, can_rx_fifo_num_type fifo_number); +uint8_t can_receive_message_pending_get(can_type* can_x, can_rx_fifo_num_type fifo_number); +error_status can_operating_mode_set(can_type* can_x, can_operating_mode_type can_operating_mode); +can_enter_doze_status_type can_doze_mode_enter(can_type* can_x); +can_quit_doze_status_type can_doze_mode_exit(can_type* can_x); +can_error_record_type can_error_type_record_get(can_type* can_x); +uint8_t can_receive_error_counter_get(can_type* can_x); +uint8_t can_transmit_error_counter_get(can_type* can_x); +void can_interrupt_enable(can_type* can_x, uint32_t can_int, confirm_state new_state); +flag_status can_flag_get(can_type* can_x, uint32_t can_flag); +void can_flag_clear(can_type* can_x, uint32_t can_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h new file mode 100644 index 0000000000..df3f882816 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h @@ -0,0 +1,172 @@ +/** + ************************************************************************** + * @file at32f435_437_crc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 crc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CRC_H +#define __AT32F435_437_CRC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/** @defgroup CRC_exported_types + * @{ + */ + +/** + * @brief crc reverse input data + */ +typedef enum +{ + CRC_REVERSE_INPUT_NO_AFFECTE = 0x00, /*!< input data no reverse */ + CRC_REVERSE_INPUT_BY_BYTE = 0x01, /*!< input data reverse by byte */ + CRC_REVERSE_INPUT_BY_HALFWORD = 0x02, /*!< input data reverse by half word */ + CRC_REVERSE_INPUT_BY_WORD = 0x03 /*!< input data reverse by word */ +} crc_reverse_input_type; + +/** + * @brief crc reverse output data + */ +typedef enum +{ + CRC_REVERSE_OUTPUT_NO_AFFECTE = 0x00, /*!< output data no reverse */ + CRC_REVERSE_OUTPUT_DATA = 0x01 /*!< output data reverse by word */ +} crc_reverse_output_type; + +/** + * @brief type define crc register all + */ +typedef struct +{ + /** + * @brief crc dt register, offset:0x00 + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 32; /* [31:0] */ + } dt_bit; + }; + + /** + * @brief crc cdt register, offset:0x04 + */ + union + { + __IO uint32_t cdt; + struct + { + __IO uint32_t cdt : 8 ; /* [7:0] */ + __IO uint32_t reserved1 : 24 ;/* [31:8] */ + } cdt_bit; + }; + + /** + * @brief crc ctrl register, offset:0x08 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t rst : 1 ; /* [0] */ + __IO uint32_t reserved1 : 4 ; /* [4:1] */ + __IO uint32_t revid : 2 ; /* [6:5] */ + __IO uint32_t revod : 1 ; /* [7] */ + __IO uint32_t reserved2 : 24 ;/* [31:8] */ + } ctrl_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x0C + */ + __IO uint32_t reserved1; + + /** + * @brief crc idt register, offset:0x10 + */ + union + { + __IO uint32_t idt; + struct + { + __IO uint32_t idt : 32; /* [31:0] */ + } idt_bit; + }; + +} crc_type; + +/** + * @} + */ + +#define CRC ((crc_type *) CRC_BASE) + +/** @defgroup CRC_exported_functions + * @{ + */ + +void crc_data_reset(void); +uint32_t crc_one_word_calculate(uint32_t data); +uint32_t crc_block_calculate(uint32_t *pbuffer, uint32_t length); +uint32_t crc_data_get(void); +void crc_common_data_set(uint8_t cdt_value); +uint8_t crc_common_data_get(void); +void crc_init_data_set(uint32_t value); +void crc_reverse_input_data_set(crc_reverse_input_type value); +void crc_reverse_output_data_set(crc_reverse_output_type value); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h new file mode 100644 index 0000000000..09ed2fa29a --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h @@ -0,0 +1,1572 @@ +/** + ************************************************************************** + * @file at32f435_437_crm.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 crm header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CRM_H +#define __AT32F435_437_CRM_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CRM + * @{ + */ + +#define CRM_REG(value) PERIPH_REG(CRM_BASE, value) +#define CRM_REG_BIT(value) PERIPH_REG_BIT(value) + +/** @defgroup CRM_flags_definition + * @brief crm flag + * @{ + */ + +#define CRM_HICK_STABLE_FLAG MAKE_VALUE(0x00, 1) /*!< high speed internal clock stable flag */ +#define CRM_HEXT_STABLE_FLAG MAKE_VALUE(0x00, 17) /*!< high speed external crystal stable flag */ +#define CRM_PLL_STABLE_FLAG MAKE_VALUE(0x00, 25) /*!< phase locking loop stable flag */ +#define CRM_LEXT_STABLE_FLAG MAKE_VALUE(0x70, 1) /*!< low speed external crystal stable flag */ +#define CRM_LICK_STABLE_FLAG MAKE_VALUE(0x74, 1) /*!< low speed internal clock stable flag */ +#define CRM_ALL_RESET_FLAG MAKE_VALUE(0x74, 24) /*!< all reset flag */ +#define CRM_NRST_RESET_FLAG MAKE_VALUE(0x74, 26) /*!< nrst pin reset flag */ +#define CRM_POR_RESET_FLAG MAKE_VALUE(0x74, 27) /*!< power on reset flag */ +#define CRM_SW_RESET_FLAG MAKE_VALUE(0x74, 28) /*!< software reset flag */ +#define CRM_WDT_RESET_FLAG MAKE_VALUE(0x74, 29) /*!< watchdog timer reset flag */ +#define CRM_WWDT_RESET_FLAG MAKE_VALUE(0x74, 30) /*!< window watchdog timer reset flag */ +#define CRM_LOWPOWER_RESET_FLAG MAKE_VALUE(0x74, 31) /*!< low-power reset flag */ +#define CRM_LICK_READY_INT_FLAG MAKE_VALUE(0x0C, 0) /*!< low speed internal clock stable interrupt ready flag */ +#define CRM_LEXT_READY_INT_FLAG MAKE_VALUE(0x0C, 1) /*!< low speed external crystal stable interrupt ready flag */ +#define CRM_HICK_READY_INT_FLAG MAKE_VALUE(0x0C, 2) /*!< high speed internal clock stable interrupt ready flag */ +#define CRM_HEXT_READY_INT_FLAG MAKE_VALUE(0x0C, 3) /*!< high speed external crystal stable interrupt ready flag */ +#define CRM_PLL_READY_INT_FLAG MAKE_VALUE(0x0C, 4) /*!< phase locking loop stable interrupt ready flag */ +#define CRM_CLOCK_FAILURE_INT_FLAG MAKE_VALUE(0x0C, 7) /*!< clock failure interrupt ready flag */ + +/** + * @} + */ + +/** @defgroup CRM_interrupts_definition + * @brief crm interrupt + * @{ + */ + +#define CRM_LICK_STABLE_INT ((uint32_t)0x00000100) /*!< low speed internal clock stable interrupt */ +#define CRM_LEXT_STABLE_INT ((uint32_t)0x00000200) /*!< low speed external crystal stable interrupt */ +#define CRM_HICK_STABLE_INT ((uint32_t)0x00000400) /*!< high speed internal clock stable interrupt */ +#define CRM_HEXT_STABLE_INT ((uint32_t)0x00000800) /*!< high speed external crystal stable interrupt */ +#define CRM_PLL_STABLE_INT ((uint32_t)0x00001000) /*!< phase locking loop stable interrupt */ +#define CRM_CLOCK_FAILURE_INT ((uint32_t)0x00800000) /*!< clock failure interrupt */ + +/** + * @} + */ + +/** @defgroup CRM_exported_types + * @{ + */ + +/** + * @brief crm periph clock + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_CLOCK = MAKE_VALUE(0x30, 0), /*!< gpioa periph clock */ + CRM_GPIOB_PERIPH_CLOCK = MAKE_VALUE(0x30, 1), /*!< gpiob periph clock */ + CRM_GPIOC_PERIPH_CLOCK = MAKE_VALUE(0x30, 2), /*!< gpioc periph clock */ + CRM_GPIOD_PERIPH_CLOCK = MAKE_VALUE(0x30, 3), /*!< gpiod periph clock */ + CRM_GPIOE_PERIPH_CLOCK = MAKE_VALUE(0x30, 4), /*!< gpioe periph clock */ + CRM_GPIOF_PERIPH_CLOCK = MAKE_VALUE(0x30, 5), /*!< gpiof periph clock */ + CRM_GPIOG_PERIPH_CLOCK = MAKE_VALUE(0x30, 6), /*!< gpiog periph clock */ + CRM_GPIOH_PERIPH_CLOCK = MAKE_VALUE(0x30, 7), /*!< gpioh periph clock */ + CRM_CRC_PERIPH_CLOCK = MAKE_VALUE(0x30, 12), /*!< crc periph clock */ + CRM_EDMA_PERIPH_CLOCK = MAKE_VALUE(0x30, 21), /*!< edma periph clock */ + CRM_DMA1_PERIPH_CLOCK = MAKE_VALUE(0x30, 22), /*!< dma1 periph clock */ + CRM_DMA2_PERIPH_CLOCK = MAKE_VALUE(0x30, 24), /*!< dma2 periph clock */ + CRM_OTGFS2_PERIPH_CLOCK = MAKE_VALUE(0x30, 29), /*!< otgfs2 periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_CLOCK = MAKE_VALUE(0x34, 0), /*!< dvp periph clock */ + CRM_OTGFS1_PERIPH_CLOCK = MAKE_VALUE(0x34, 7), /*!< otgfs1 periph clock */ + CRM_SDIO1_PERIPH_CLOCK = MAKE_VALUE(0x34, 15), /*!< sdio1 periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_CLOCK = MAKE_VALUE(0x38, 0), /*!< xmc periph clock */ + CRM_QSPI1_PERIPH_CLOCK = MAKE_VALUE(0x38, 1), /*!< qspi1 periph clock */ + CRM_QSPI2_PERIPH_CLOCK = MAKE_VALUE(0x38, 14), /*!< qspi2 periph clock */ + CRM_SDIO2_PERIPH_CLOCK = MAKE_VALUE(0x38, 15), /*!< sdio2 periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_CLOCK = MAKE_VALUE(0x40, 0), /*!< tmr2 periph clock */ + CRM_TMR3_PERIPH_CLOCK = MAKE_VALUE(0x40, 1), /*!< tmr3 periph clock */ + CRM_TMR4_PERIPH_CLOCK = MAKE_VALUE(0x40, 2), /*!< tmr4 periph clock */ + CRM_TMR5_PERIPH_CLOCK = MAKE_VALUE(0x40, 3), /*!< tmr5 periph clock */ + CRM_TMR6_PERIPH_CLOCK = MAKE_VALUE(0x40, 4), /*!< tmr6 periph clock */ + CRM_TMR7_PERIPH_CLOCK = MAKE_VALUE(0x40, 5), /*!< tmr7 periph clock */ + CRM_TMR12_PERIPH_CLOCK = MAKE_VALUE(0x40, 6), /*!< tmr12 periph clock */ + CRM_TMR13_PERIPH_CLOCK = MAKE_VALUE(0x40, 7), /*!< tmr13 periph clock */ + CRM_TMR14_PERIPH_CLOCK = MAKE_VALUE(0x40, 8), /*!< tmr14 periph clock */ + CRM_WWDT_PERIPH_CLOCK = MAKE_VALUE(0x40, 11), /*!< wwdt periph clock */ + CRM_SPI2_PERIPH_CLOCK = MAKE_VALUE(0x40, 14), /*!< spi2 periph clock */ + CRM_SPI3_PERIPH_CLOCK = MAKE_VALUE(0x40, 15), /*!< spi3 periph clock */ + CRM_USART2_PERIPH_CLOCK = MAKE_VALUE(0x40, 17), /*!< usart2 periph clock */ + CRM_USART3_PERIPH_CLOCK = MAKE_VALUE(0x40, 18), /*!< usart3 periph clock */ + CRM_UART4_PERIPH_CLOCK = MAKE_VALUE(0x40, 19), /*!< uart4 periph clock */ + CRM_UART5_PERIPH_CLOCK = MAKE_VALUE(0x40, 20), /*!< uart5 periph clock */ + CRM_I2C1_PERIPH_CLOCK = MAKE_VALUE(0x40, 21), /*!< i2c1 periph clock */ + CRM_I2C2_PERIPH_CLOCK = MAKE_VALUE(0x40, 22), /*!< i2c2 periph clock */ + CRM_I2C3_PERIPH_CLOCK = MAKE_VALUE(0x40, 23), /*!< i2c3 periph clock */ + CRM_CAN1_PERIPH_CLOCK = MAKE_VALUE(0x40, 25), /*!< can1 periph clock */ + CRM_CAN2_PERIPH_CLOCK = MAKE_VALUE(0x40, 26), /*!< can2 periph clock */ + CRM_PWC_PERIPH_CLOCK = MAKE_VALUE(0x40, 28), /*!< pwc periph clock */ + CRM_DAC_PERIPH_CLOCK = MAKE_VALUE(0x40, 29), /*!< dac periph clock */ + CRM_UART7_PERIPH_CLOCK = MAKE_VALUE(0x40, 30), /*!< uart7 periph clock */ + CRM_UART8_PERIPH_CLOCK = MAKE_VALUE(0x40, 31), /*!< uart8 periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_CLOCK = MAKE_VALUE(0x44, 0), /*!< tmr1 periph clock */ + CRM_TMR8_PERIPH_CLOCK = MAKE_VALUE(0x44, 1), /*!< tmr8 periph clock */ + CRM_USART1_PERIPH_CLOCK = MAKE_VALUE(0x44, 4), /*!< usart1 periph clock */ + CRM_USART6_PERIPH_CLOCK = MAKE_VALUE(0x44, 5), /*!< usart6 periph clock */ + CRM_ADC1_PERIPH_CLOCK = MAKE_VALUE(0x44, 8), /*!< adc1 periph clock */ + CRM_ADC2_PERIPH_CLOCK = MAKE_VALUE(0x44, 9), /*!< adc2 periph clock */ + CRM_ADC3_PERIPH_CLOCK = MAKE_VALUE(0x44, 10), /*!< adc3 periph clock */ + CRM_SPI1_PERIPH_CLOCK = MAKE_VALUE(0x44, 12), /*!< spi1 periph clock */ + CRM_SPI4_PERIPH_CLOCK = MAKE_VALUE(0x44, 13), /*!< spi4 periph clock */ + CRM_SCFG_PERIPH_CLOCK = MAKE_VALUE(0x44, 14), /*!< scfg periph clock */ + CRM_TMR9_PERIPH_CLOCK = MAKE_VALUE(0x44, 16), /*!< tmr9 periph clock */ + CRM_TMR10_PERIPH_CLOCK = MAKE_VALUE(0x44, 17), /*!< tmr10 periph clock */ + CRM_TMR11_PERIPH_CLOCK = MAKE_VALUE(0x44, 18), /*!< tmr11 periph clock */ + CRM_TMR20_PERIPH_CLOCK = MAKE_VALUE(0x44, 20), /*!< tmr20 periph clock */ + CRM_ACC_PERIPH_CLOCK = MAKE_VALUE(0x44, 29) /*!< acc periph clock */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_CLOCK = MAKE_VALUE(0x30, 0), /*!< gpioa periph clock */ + CRM_GPIOB_PERIPH_CLOCK = MAKE_VALUE(0x30, 1), /*!< gpiob periph clock */ + CRM_GPIOC_PERIPH_CLOCK = MAKE_VALUE(0x30, 2), /*!< gpioc periph clock */ + CRM_GPIOD_PERIPH_CLOCK = MAKE_VALUE(0x30, 3), /*!< gpiod periph clock */ + CRM_GPIOE_PERIPH_CLOCK = MAKE_VALUE(0x30, 4), /*!< gpioe periph clock */ + CRM_GPIOF_PERIPH_CLOCK = MAKE_VALUE(0x30, 5), /*!< gpiof periph clock */ + CRM_GPIOG_PERIPH_CLOCK = MAKE_VALUE(0x30, 6), /*!< gpiog periph clock */ + CRM_GPIOH_PERIPH_CLOCK = MAKE_VALUE(0x30, 7), /*!< gpioh periph clock */ + CRM_CRC_PERIPH_CLOCK = MAKE_VALUE(0x30, 12), /*!< crc periph clock */ + CRM_EDMA_PERIPH_CLOCK = MAKE_VALUE(0x30, 21), /*!< edma periph clock */ + CRM_DMA1_PERIPH_CLOCK = MAKE_VALUE(0x30, 22), /*!< dma1 periph clock */ + CRM_DMA2_PERIPH_CLOCK = MAKE_VALUE(0x30, 24), /*!< dma2 periph clock */ + CRM_EMAC_PERIPH_CLOCK = MAKE_VALUE(0x30, 25), /*!< emac periph clock */ + CRM_EMACTX_PERIPH_CLOCK = MAKE_VALUE(0x30, 26), /*!< emac tx periph clock */ + CRM_EMACRX_PERIPH_CLOCK = MAKE_VALUE(0x30, 27), /*!< emac rx periph clock */ + CRM_EMACPTP_PERIPH_CLOCK = MAKE_VALUE(0x30, 28), /*!< emac ptp periph clock */ + CRM_OTGFS2_PERIPH_CLOCK = MAKE_VALUE(0x30, 29), /*!< otgfs2 periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_CLOCK = MAKE_VALUE(0x34, 0), /*!< dvp periph clock */ + CRM_OTGFS1_PERIPH_CLOCK = MAKE_VALUE(0x34, 7), /*!< otgfs1 periph clock */ + CRM_SDIO1_PERIPH_CLOCK = MAKE_VALUE(0x34, 15), /*!< sdio1 periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_CLOCK = MAKE_VALUE(0x38, 0), /*!< xmc periph clock */ + CRM_QSPI1_PERIPH_CLOCK = MAKE_VALUE(0x38, 1), /*!< qspi1 periph clock */ + CRM_QSPI2_PERIPH_CLOCK = MAKE_VALUE(0x38, 14), /*!< qspi2 periph clock */ + CRM_SDIO2_PERIPH_CLOCK = MAKE_VALUE(0x38, 15), /*!< sdio2 periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_CLOCK = MAKE_VALUE(0x40, 0), /*!< tmr2 periph clock */ + CRM_TMR3_PERIPH_CLOCK = MAKE_VALUE(0x40, 1), /*!< tmr3 periph clock */ + CRM_TMR4_PERIPH_CLOCK = MAKE_VALUE(0x40, 2), /*!< tmr4 periph clock */ + CRM_TMR5_PERIPH_CLOCK = MAKE_VALUE(0x40, 3), /*!< tmr5 periph clock */ + CRM_TMR6_PERIPH_CLOCK = MAKE_VALUE(0x40, 4), /*!< tmr6 periph clock */ + CRM_TMR7_PERIPH_CLOCK = MAKE_VALUE(0x40, 5), /*!< tmr7 periph clock */ + CRM_TMR12_PERIPH_CLOCK = MAKE_VALUE(0x40, 6), /*!< tmr12 periph clock */ + CRM_TMR13_PERIPH_CLOCK = MAKE_VALUE(0x40, 7), /*!< tmr13 periph clock */ + CRM_TMR14_PERIPH_CLOCK = MAKE_VALUE(0x40, 8), /*!< tmr14 periph clock */ + CRM_WWDT_PERIPH_CLOCK = MAKE_VALUE(0x40, 11), /*!< wwdt periph clock */ + CRM_SPI2_PERIPH_CLOCK = MAKE_VALUE(0x40, 14), /*!< spi2 periph clock */ + CRM_SPI3_PERIPH_CLOCK = MAKE_VALUE(0x40, 15), /*!< spi3 periph clock */ + CRM_USART2_PERIPH_CLOCK = MAKE_VALUE(0x40, 17), /*!< usart2 periph clock */ + CRM_USART3_PERIPH_CLOCK = MAKE_VALUE(0x40, 18), /*!< usart3 periph clock */ + CRM_UART4_PERIPH_CLOCK = MAKE_VALUE(0x40, 19), /*!< uart4 periph clock */ + CRM_UART5_PERIPH_CLOCK = MAKE_VALUE(0x40, 20), /*!< uart5 periph clock */ + CRM_I2C1_PERIPH_CLOCK = MAKE_VALUE(0x40, 21), /*!< i2c1 periph clock */ + CRM_I2C2_PERIPH_CLOCK = MAKE_VALUE(0x40, 22), /*!< i2c2 periph clock */ + CRM_I2C3_PERIPH_CLOCK = MAKE_VALUE(0x40, 23), /*!< i2c3 periph clock */ + CRM_CAN1_PERIPH_CLOCK = MAKE_VALUE(0x40, 25), /*!< can1 periph clock */ + CRM_CAN2_PERIPH_CLOCK = MAKE_VALUE(0x40, 26), /*!< can2 periph clock */ + CRM_PWC_PERIPH_CLOCK = MAKE_VALUE(0x40, 28), /*!< pwc periph clock */ + CRM_DAC_PERIPH_CLOCK = MAKE_VALUE(0x40, 29), /*!< dac periph clock */ + CRM_UART7_PERIPH_CLOCK = MAKE_VALUE(0x40, 30), /*!< uart7 periph clock */ + CRM_UART8_PERIPH_CLOCK = MAKE_VALUE(0x40, 31), /*!< uart8 periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_CLOCK = MAKE_VALUE(0x44, 0), /*!< tmr1 periph clock */ + CRM_TMR8_PERIPH_CLOCK = MAKE_VALUE(0x44, 1), /*!< tmr8 periph clock */ + CRM_USART1_PERIPH_CLOCK = MAKE_VALUE(0x44, 4), /*!< usart1 periph clock */ + CRM_USART6_PERIPH_CLOCK = MAKE_VALUE(0x44, 5), /*!< usart6 periph clock */ + CRM_ADC1_PERIPH_CLOCK = MAKE_VALUE(0x44, 8), /*!< adc1 periph clock */ + CRM_ADC2_PERIPH_CLOCK = MAKE_VALUE(0x44, 9), /*!< adc2 periph clock */ + CRM_ADC3_PERIPH_CLOCK = MAKE_VALUE(0x44, 10), /*!< adc3 periph clock */ + CRM_SPI1_PERIPH_CLOCK = MAKE_VALUE(0x44, 12), /*!< spi1 periph clock */ + CRM_SPI4_PERIPH_CLOCK = MAKE_VALUE(0x44, 13), /*!< spi4 periph clock */ + CRM_SCFG_PERIPH_CLOCK = MAKE_VALUE(0x44, 14), /*!< scfg periph clock */ + CRM_TMR9_PERIPH_CLOCK = MAKE_VALUE(0x44, 16), /*!< tmr9 periph clock */ + CRM_TMR10_PERIPH_CLOCK = MAKE_VALUE(0x44, 17), /*!< tmr10 periph clock */ + CRM_TMR11_PERIPH_CLOCK = MAKE_VALUE(0x44, 18), /*!< tmr11 periph clock */ + CRM_TMR20_PERIPH_CLOCK = MAKE_VALUE(0x44, 20), /*!< tmr20 periph clock */ + CRM_ACC_PERIPH_CLOCK = MAKE_VALUE(0x44, 29) /*!< acc periph clock */ +#endif + +} crm_periph_clock_type; + +/** + * @brief crm periph reset + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_RESET = MAKE_VALUE(0x10, 0), /*!< gpioa periph reset */ + CRM_GPIOB_PERIPH_RESET = MAKE_VALUE(0x10, 1), /*!< gpiob periph reset */ + CRM_GPIOC_PERIPH_RESET = MAKE_VALUE(0x10, 2), /*!< gpioc periph reset */ + CRM_GPIOD_PERIPH_RESET = MAKE_VALUE(0x10, 3), /*!< gpiod periph reset */ + CRM_GPIOE_PERIPH_RESET = MAKE_VALUE(0x10, 4), /*!< gpioe periph reset */ + CRM_GPIOF_PERIPH_RESET = MAKE_VALUE(0x10, 5), /*!< gpiof periph reset */ + CRM_GPIOG_PERIPH_RESET = MAKE_VALUE(0x10, 6), /*!< gpiog periph reset */ + CRM_GPIOH_PERIPH_RESET = MAKE_VALUE(0x10, 7), /*!< gpioh periph reset */ + CRM_CRC_PERIPH_RESET = MAKE_VALUE(0x10, 12), /*!< crc periph reset */ + CRM_EDMA_PERIPH_RESET = MAKE_VALUE(0x10, 21), /*!< edma periph reset */ + CRM_DMA1_PERIPH_RESET = MAKE_VALUE(0x10, 22), /*!< dma1 periph reset */ + CRM_DMA2_PERIPH_RESET = MAKE_VALUE(0x10, 24), /*!< dma2 periph reset */ + CRM_OTGFS2_PERIPH_RESET = MAKE_VALUE(0x10, 29), /*!< otgfs2 periph reset */ + /* ahb periph2 */ + CRM_DVP_PERIPH_RESET = MAKE_VALUE(0x14, 0), /*!< dvp periph reset */ + CRM_OTGFS1_PERIPH_RESET = MAKE_VALUE(0x14, 7), /*!< otgfs1 periph reset */ + CRM_SDIO1_PERIPH_RESET = MAKE_VALUE(0x14, 15), /*!< sdio1 periph reset */ + /* ahb periph3 */ + CRM_XMC_PERIPH_RESET = MAKE_VALUE(0x18, 0), /*!< xmc periph reset */ + CRM_QSPI1_PERIPH_RESET = MAKE_VALUE(0x18, 1), /*!< qspi1 periph reset */ + CRM_QSPI2_PERIPH_RESET = MAKE_VALUE(0x18, 14), /*!< qspi2 periph reset */ + CRM_SDIO2_PERIPH_RESET = MAKE_VALUE(0x18, 15), /*!< sdio2 periph reset */ + /* apb1 periph */ + CRM_TMR2_PERIPH_RESET = MAKE_VALUE(0x20, 0), /*!< tmr2 periph reset */ + CRM_TMR3_PERIPH_RESET = MAKE_VALUE(0x20, 1), /*!< tmr3 periph reset */ + CRM_TMR4_PERIPH_RESET = MAKE_VALUE(0x20, 2), /*!< tmr4 periph reset */ + CRM_TMR5_PERIPH_RESET = MAKE_VALUE(0x20, 3), /*!< tmr5 periph reset */ + CRM_TMR6_PERIPH_RESET = MAKE_VALUE(0x20, 4), /*!< tmr6 periph reset */ + CRM_TMR7_PERIPH_RESET = MAKE_VALUE(0x20, 5), /*!< tmr7 periph reset */ + CRM_TMR12_PERIPH_RESET = MAKE_VALUE(0x20, 6), /*!< tmr12 periph reset */ + CRM_TMR13_PERIPH_RESET = MAKE_VALUE(0x20, 7), /*!< tmr13 periph reset */ + CRM_TMR14_PERIPH_RESET = MAKE_VALUE(0x20, 8), /*!< tmr14 periph reset */ + CRM_WWDT_PERIPH_RESET = MAKE_VALUE(0x20, 11), /*!< wwdt periph reset */ + CRM_SPI2_PERIPH_RESET = MAKE_VALUE(0x20, 14), /*!< spi2 periph reset */ + CRM_SPI3_PERIPH_RESET = MAKE_VALUE(0x20, 15), /*!< spi3 periph reset */ + CRM_USART2_PERIPH_RESET = MAKE_VALUE(0x20, 17), /*!< usart2 periph reset */ + CRM_USART3_PERIPH_RESET = MAKE_VALUE(0x20, 18), /*!< usart3 periph reset */ + CRM_UART4_PERIPH_RESET = MAKE_VALUE(0x20, 19), /*!< uart4 periph reset */ + CRM_UART5_PERIPH_RESET = MAKE_VALUE(0x20, 20), /*!< uart5 periph reset */ + CRM_I2C1_PERIPH_RESET = MAKE_VALUE(0x20, 21), /*!< i2c1 periph reset */ + CRM_I2C2_PERIPH_RESET = MAKE_VALUE(0x20, 22), /*!< i2c2 periph reset */ + CRM_I2C3_PERIPH_RESET = MAKE_VALUE(0x20, 23), /*!< i2c3 periph reset */ + CRM_CAN1_PERIPH_RESET = MAKE_VALUE(0x20, 25), /*!< can1 periph reset */ + CRM_CAN2_PERIPH_RESET = MAKE_VALUE(0x20, 26), /*!< can2 periph reset */ + CRM_PWC_PERIPH_RESET = MAKE_VALUE(0x20, 28), /*!< pwc periph reset */ + CRM_DAC_PERIPH_RESET = MAKE_VALUE(0x20, 29), /*!< dac periph reset */ + CRM_UART7_PERIPH_RESET = MAKE_VALUE(0x20, 30), /*!< uart7 periph reset */ + CRM_UART8_PERIPH_RESET = MAKE_VALUE(0x20, 31), /*!< uart8 periph reset */ + /* apb2 periph */ + CRM_TMR1_PERIPH_RESET = MAKE_VALUE(0x24, 0), /*!< tmr1 periph reset */ + CRM_TMR8_PERIPH_RESET = MAKE_VALUE(0x24, 1), /*!< tmr8 periph reset */ + CRM_USART1_PERIPH_RESET = MAKE_VALUE(0x24, 4), /*!< usart1 periph reset */ + CRM_USART6_PERIPH_RESET = MAKE_VALUE(0x24, 5), /*!< usart6 periph reset */ + CRM_ADC_PERIPH_RESET = MAKE_VALUE(0x24, 8), /*!< adc periph reset */ + CRM_SPI1_PERIPH_RESET = MAKE_VALUE(0x24, 12), /*!< spi1 periph reset */ + CRM_SPI4_PERIPH_RESET = MAKE_VALUE(0x24, 13), /*!< spi4 periph reset */ + CRM_SCFG_PERIPH_RESET = MAKE_VALUE(0x24, 14), /*!< scfg periph reset */ + CRM_TMR9_PERIPH_RESET = MAKE_VALUE(0x24, 16), /*!< tmr9 periph reset */ + CRM_TMR10_PERIPH_RESET = MAKE_VALUE(0x24, 17), /*!< tmr10 periph reset */ + CRM_TMR11_PERIPH_RESET = MAKE_VALUE(0x24, 18), /*!< tmr11 periph reset */ + CRM_TMR20_PERIPH_RESET = MAKE_VALUE(0x24, 20), /*!< tmr20 periph reset */ + CRM_ACC_PERIPH_RESET = MAKE_VALUE(0x24, 29) /*!< acc periph reset */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_RESET = MAKE_VALUE(0x10, 0), /*!< gpioa periph reset */ + CRM_GPIOB_PERIPH_RESET = MAKE_VALUE(0x10, 1), /*!< gpiob periph reset */ + CRM_GPIOC_PERIPH_RESET = MAKE_VALUE(0x10, 2), /*!< gpioc periph reset */ + CRM_GPIOD_PERIPH_RESET = MAKE_VALUE(0x10, 3), /*!< gpiod periph reset */ + CRM_GPIOE_PERIPH_RESET = MAKE_VALUE(0x10, 4), /*!< gpioe periph reset */ + CRM_GPIOF_PERIPH_RESET = MAKE_VALUE(0x10, 5), /*!< gpiof periph reset */ + CRM_GPIOG_PERIPH_RESET = MAKE_VALUE(0x10, 6), /*!< gpiog periph reset */ + CRM_GPIOH_PERIPH_RESET = MAKE_VALUE(0x10, 7), /*!< gpioh periph reset */ + CRM_CRC_PERIPH_RESET = MAKE_VALUE(0x10, 12), /*!< crc periph reset */ + CRM_EDMA_PERIPH_RESET = MAKE_VALUE(0x10, 21), /*!< edma periph reset */ + CRM_DMA1_PERIPH_RESET = MAKE_VALUE(0x10, 22), /*!< dma1 periph reset */ + CRM_DMA2_PERIPH_RESET = MAKE_VALUE(0x10, 24), /*!< dma2 periph reset */ + CRM_EMAC_PERIPH_RESET = MAKE_VALUE(0x10, 25), /*!< emac periph reset */ + CRM_OTGFS2_PERIPH_RESET = MAKE_VALUE(0x10, 29), /*!< otgfs2 periph reset */ + /* ahb periph2 */ + CRM_DVP_PERIPH_RESET = MAKE_VALUE(0x14, 0), /*!< dvp periph reset */ + CRM_OTGFS1_PERIPH_RESET = MAKE_VALUE(0x14, 7), /*!< otgfs1 periph reset */ + CRM_SDIO1_PERIPH_RESET = MAKE_VALUE(0x14, 15), /*!< sdio1 periph reset */ + /* ahb periph3 */ + CRM_XMC_PERIPH_RESET = MAKE_VALUE(0x18, 0), /*!< xmc periph reset */ + CRM_QSPI1_PERIPH_RESET = MAKE_VALUE(0x18, 1), /*!< qspi1 periph reset */ + CRM_QSPI2_PERIPH_RESET = MAKE_VALUE(0x18, 14), /*!< qspi2 periph reset */ + CRM_SDIO2_PERIPH_RESET = MAKE_VALUE(0x18, 15), /*!< sdio2 periph reset */ + /* apb1 periph */ + CRM_TMR2_PERIPH_RESET = MAKE_VALUE(0x20, 0), /*!< tmr2 periph reset */ + CRM_TMR3_PERIPH_RESET = MAKE_VALUE(0x20, 1), /*!< tmr3 periph reset */ + CRM_TMR4_PERIPH_RESET = MAKE_VALUE(0x20, 2), /*!< tmr4 periph reset */ + CRM_TMR5_PERIPH_RESET = MAKE_VALUE(0x20, 3), /*!< tmr5 periph reset */ + CRM_TMR6_PERIPH_RESET = MAKE_VALUE(0x20, 4), /*!< tmr6 periph reset */ + CRM_TMR7_PERIPH_RESET = MAKE_VALUE(0x20, 5), /*!< tmr7 periph reset */ + CRM_TMR12_PERIPH_RESET = MAKE_VALUE(0x20, 6), /*!< tmr12 periph reset */ + CRM_TMR13_PERIPH_RESET = MAKE_VALUE(0x20, 7), /*!< tmr13 periph reset */ + CRM_TMR14_PERIPH_RESET = MAKE_VALUE(0x20, 8), /*!< tmr14 periph reset */ + CRM_WWDT_PERIPH_RESET = MAKE_VALUE(0x20, 11), /*!< wwdt periph reset */ + CRM_SPI2_PERIPH_RESET = MAKE_VALUE(0x20, 14), /*!< spi2 periph reset */ + CRM_SPI3_PERIPH_RESET = MAKE_VALUE(0x20, 15), /*!< spi3 periph reset */ + CRM_USART2_PERIPH_RESET = MAKE_VALUE(0x20, 17), /*!< usart2 periph reset */ + CRM_USART3_PERIPH_RESET = MAKE_VALUE(0x20, 18), /*!< usart3 periph reset */ + CRM_UART4_PERIPH_RESET = MAKE_VALUE(0x20, 19), /*!< uart4 periph reset */ + CRM_UART5_PERIPH_RESET = MAKE_VALUE(0x20, 20), /*!< uart5 periph reset */ + CRM_I2C1_PERIPH_RESET = MAKE_VALUE(0x20, 21), /*!< i2c1 periph reset */ + CRM_I2C2_PERIPH_RESET = MAKE_VALUE(0x20, 22), /*!< i2c2 periph reset */ + CRM_I2C3_PERIPH_RESET = MAKE_VALUE(0x20, 23), /*!< i2c3 periph reset */ + CRM_CAN1_PERIPH_RESET = MAKE_VALUE(0x20, 25), /*!< can1 periph reset */ + CRM_CAN2_PERIPH_RESET = MAKE_VALUE(0x20, 26), /*!< can2 periph reset */ + CRM_PWC_PERIPH_RESET = MAKE_VALUE(0x20, 28), /*!< pwc periph reset */ + CRM_DAC_PERIPH_RESET = MAKE_VALUE(0x20, 29), /*!< dac periph reset */ + CRM_UART7_PERIPH_RESET = MAKE_VALUE(0x20, 30), /*!< uart7 periph reset */ + CRM_UART8_PERIPH_RESET = MAKE_VALUE(0x20, 31), /*!< uart8 periph reset */ + /* apb2 periph */ + CRM_TMR1_PERIPH_RESET = MAKE_VALUE(0x24, 0), /*!< tmr1 periph reset */ + CRM_TMR8_PERIPH_RESET = MAKE_VALUE(0x24, 1), /*!< tmr8 periph reset */ + CRM_USART1_PERIPH_RESET = MAKE_VALUE(0x24, 4), /*!< usart1 periph reset */ + CRM_USART6_PERIPH_RESET = MAKE_VALUE(0x24, 5), /*!< usart6 periph reset */ + CRM_ADC_PERIPH_RESET = MAKE_VALUE(0x24, 8), /*!< adc periph reset */ + CRM_SPI1_PERIPH_RESET = MAKE_VALUE(0x24, 12), /*!< spi1 periph reset */ + CRM_SPI4_PERIPH_RESET = MAKE_VALUE(0x24, 13), /*!< spi4 periph reset */ + CRM_SCFG_PERIPH_RESET = MAKE_VALUE(0x24, 14), /*!< scfg periph reset */ + CRM_TMR9_PERIPH_RESET = MAKE_VALUE(0x24, 16), /*!< tmr9 periph reset */ + CRM_TMR10_PERIPH_RESET = MAKE_VALUE(0x24, 17), /*!< tmr10 periph reset */ + CRM_TMR11_PERIPH_RESET = MAKE_VALUE(0x24, 18), /*!< tmr11 periph reset */ + CRM_TMR20_PERIPH_RESET = MAKE_VALUE(0x24, 20), /*!< tmr20 periph reset */ + CRM_ACC_PERIPH_RESET = MAKE_VALUE(0x24, 29) /*!< acc periph reset */ +#endif + +} crm_periph_reset_type; + +/** + * @brief crm periph clock in low power mode + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 0), /*!< gpioa sleep mode periph clock */ + CRM_GPIOB_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 1), /*!< gpiob sleep mode periph clock */ + CRM_GPIOC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 2), /*!< gpioc sleep mode periph clock */ + CRM_GPIOD_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 3), /*!< gpiod sleep mode periph clock */ + CRM_GPIOE_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 4), /*!< gpioe sleep mode periph clock */ + CRM_GPIOF_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 5), /*!< gpiof sleep mode periph clock */ + CRM_GPIOG_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 6), /*!< gpiog sleep mode periph clock */ + CRM_GPIOH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 7), /*!< gpioh sleep mode periph clock */ + CRM_CRC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 12), /*!< crc sleep mode periph clock */ + CRM_FLASH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 15), /*!< flash sleep mode periph clock */ + CRM_SRAM1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 16), /*!< sram1 sleep mode periph clock */ + CRM_SRAM2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 17), /*!< sram2 sleep mode periph clock */ + CRM_EDMA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 21), /*!< edma sleep mode periph clock */ + CRM_DMA1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 22), /*!< dma1 sleep mode periph clock */ + CRM_DMA2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 24), /*!< dma2 sleep mode periph clock */ + CRM_EMAC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 25), /*!< emac sleep mode periph clock */ + CRM_EMACTX_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 26), /*!< emac tx sleep mode periph clock */ + CRM_EMACRX_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 27), /*!< emac rx sleep mode periph clock */ + CRM_EMACPTP_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 28), /*!< emac ptp sleep mode periph clock */ + CRM_OTGFS2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 29), /*!< otgfs2 sleep mode periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 0), /*!< dvp sleep mode periph clock */ + CRM_OTGFS1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 7), /*!< otgfs1 sleep mode periph clock */ + CRM_SDIO1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 15), /*!< sdio1 sleep mode periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 0), /*!< xmc sleep mode periph clock */ + CRM_QSPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 1), /*!< qspi1 sleep mode periph clock */ + CRM_QSPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 14), /*!< qspi2 sleep mode periph clock */ + CRM_SDIO2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 15), /*!< sdio2 sleep mode periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 0), /*!< tmr2 sleep mode periph clock */ + CRM_TMR3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 1), /*!< tmr3 sleep mode periph clock */ + CRM_TMR4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 2), /*!< tmr4 sleep mode periph clock */ + CRM_TMR5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 3), /*!< tmr5 sleep mode periph clock */ + CRM_TMR6_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 4), /*!< tmr6 sleep mode periph clock */ + CRM_TMR7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 5), /*!< tmr7 sleep mode periph clock */ + CRM_TMR12_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 6), /*!< tmr12 sleep mode periph clock */ + CRM_TMR13_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 7), /*!< tmr13 sleep mode periph clock */ + CRM_TMR14_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 8), /*!< tmr14 sleep mode periph clock */ + CRM_WWDT_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 11), /*!< wwdt sleep mode periph clock */ + CRM_SPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 14), /*!< spi2 sleep mode periph clock */ + CRM_SPI3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 15), /*!< spi3 sleep mode periph clock */ + CRM_USART2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 17), /*!< usart2 sleep mode periph clock */ + CRM_USART3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 18), /*!< usart3 sleep mode periph clock */ + CRM_UART4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 19), /*!< uart4 sleep mode periph clock */ + CRM_UART5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 20), /*!< uart5 sleep mode periph clock */ + CRM_I2C1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 21), /*!< i2c1 sleep mode periph clock */ + CRM_I2C2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 22), /*!< i2c2 sleep mode periph clock */ + CRM_I2C3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 23), /*!< i2c3 sleep mode periph clock */ + CRM_CAN1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 25), /*!< can1 sleep mode periph clock */ + CRM_CAN2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 26), /*!< can2 sleep mode periph clock */ + CRM_PWC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 28), /*!< pwc sleep mode periph clock */ + CRM_DAC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 29), /*!< dac sleep mode periph clock */ + CRM_UART7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 30), /*!< uart7 sleep mode periph clock */ + CRM_UART8_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 31), /*!< uart8 sleep mode periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 0), /*!< tmr1 sleep mode periph clock */ + CRM_TMR8_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 1), /*!< tmr8 sleep mode periph clock */ + CRM_USART1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 4), /*!< usart1 sleep mode periph clock */ + CRM_USART6_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 5), /*!< usart6 sleep mode periph clock */ + CRM_ADC1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 8), /*!< adc1 sleep mode periph clock */ + CRM_ADC2_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 9), /*!< adc2 sleep mode periph clock */ + CRM_ADC3_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 10), /*!< adc3 sleep mode periph clock */ + CRM_SPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 12), /*!< spi1 sleep mode periph clock */ + CRM_SPI4_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 13), /*!< spi4 sleep mode periph clock */ + CRM_SCFG_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 14), /*!< scfg sleep mode periph clock */ + CRM_TMR9_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 16), /*!< tmr9 sleep mode periph clock */ + CRM_TMR10_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 17), /*!< tmr10 sleep mode periph clock */ + CRM_TMR11_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 18), /*!< tmr11 sleep mode periph clock */ + CRM_TMR20_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 20), /*!< tmr20 sleep mode periph clock */ + CRM_ACC_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 29) /*!< acc sleep mode periph clock */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 0), /*!< gpioa sleep mode periph clock */ + CRM_GPIOB_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 1), /*!< gpiob sleep mode periph clock */ + CRM_GPIOC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 2), /*!< gpioc sleep mode periph clock */ + CRM_GPIOD_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 3), /*!< gpiod sleep mode periph clock */ + CRM_GPIOE_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 4), /*!< gpioe sleep mode periph clock */ + CRM_GPIOF_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 5), /*!< gpiof sleep mode periph clock */ + CRM_GPIOG_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 6), /*!< gpiog sleep mode periph clock */ + CRM_GPIOH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 7), /*!< gpioh sleep mode periph clock */ + CRM_CRC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 12), /*!< crc sleep mode periph clock */ + CRM_FLASH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 15), /*!< flash sleep mode periph clock */ + CRM_SRAM1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 16), /*!< sram1 sleep mode periph clock */ + CRM_SRAM2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 17), /*!< sram2 sleep mode periph clock */ + CRM_EDMA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 21), /*!< edma sleep mode periph clock */ + CRM_DMA1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 22), /*!< dma1 sleep mode periph clock */ + CRM_DMA2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 24), /*!< dma2 sleep mode periph clock */ + CRM_OTGFS2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 29), /*!< otgfs2 sleep mode periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 0), /*!< dvp sleep mode periph clock */ + CRM_OTGFS1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 7), /*!< otgfs1 sleep mode periph clock */ + CRM_SDIO1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 15), /*!< sdio1 sleep mode periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 0), /*!< xmc sleep mode periph clock */ + CRM_QSPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 1), /*!< qspi1 sleep mode periph clock */ + CRM_QSPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 14), /*!< qspi2 sleep mode periph clock */ + CRM_SDIO2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 15), /*!< sdio2 sleep mode periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 0), /*!< tmr2 sleep mode periph clock */ + CRM_TMR3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 1), /*!< tmr3 sleep mode periph clock */ + CRM_TMR4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 2), /*!< tmr4 sleep mode periph clock */ + CRM_TMR5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 3), /*!< tmr5 sleep mode periph clock */ + CRM_TMR6_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 4), /*!< tmr6 sleep mode periph clock */ + CRM_TMR7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 5), /*!< tmr7 sleep mode periph clock */ + CRM_TMR12_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 6), /*!< tmr12 sleep mode periph clock */ + CRM_TMR13_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 7), /*!< tmr13 sleep mode periph clock */ + CRM_TMR14_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 8), /*!< tmr14 sleep mode periph clock */ + CRM_WWDT_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 11), /*!< wwdt sleep mode periph clock */ + CRM_SPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 14), /*!< spi2 sleep mode periph clock */ + CRM_SPI3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 15), /*!< spi3 sleep mode periph clock */ + CRM_USART2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 17), /*!< usart2 sleep mode periph clock */ + CRM_USART3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 18), /*!< usart3 sleep mode periph clock */ + CRM_UART4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 19), /*!< uart4 sleep mode periph clock */ + CRM_UART5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 20), /*!< uart5 sleep mode periph clock */ + CRM_I2C1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 21), /*!< i2c1 sleep mode periph clock */ + CRM_I2C2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 22), /*!< i2c2 sleep mode periph clock */ + CRM_I2C3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 23), /*!< i2c3 sleep mode periph clock */ + CRM_CAN1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 25), /*!< can1 sleep mode periph clock */ + CRM_CAN2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 26), /*!< can2 sleep mode periph clock */ + CRM_PWC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 28), /*!< pwc sleep mode periph clock */ + CRM_DAC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 29), /*!< dac sleep mode periph clock */ + CRM_UART7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 30), /*!< uart7 sleep mode periph clock */ + CRM_UART8_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 31), /*!< uart8 sleep mode periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 0), /*!< tmr1 sleep mode periph clock */ + CRM_TMR8_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 1), /*!< tmr8 sleep mode periph clock */ + CRM_USART1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 4), /*!< usart1 sleep mode periph clock */ + CRM_USART6_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 5), /*!< usart6 sleep mode periph clock */ + CRM_ADC1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 8), /*!< adc1 sleep mode periph clock */ + CRM_ADC2_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 9), /*!< adc2 sleep mode periph clock */ + CRM_ADC3_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 10), /*!< adc3 sleep mode periph clock */ + CRM_SPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 12), /*!< spi1 sleep mode periph clock */ + CRM_SPI4_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 13), /*!< spi4 sleep mode periph clock */ + CRM_SCFG_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 14), /*!< scfg sleep mode periph clock */ + CRM_TMR9_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 16), /*!< tmr9 sleep mode periph clock */ + CRM_TMR10_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 17), /*!< tmr10 sleep mode periph clock */ + CRM_TMR11_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 18), /*!< tmr11 sleep mode periph clock */ + CRM_TMR20_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 20), /*!< tmr20 sleep mode periph clock */ + CRM_ACC_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 29) /*!< acc sleep mode periph clock */ +#endif + +} crm_periph_clock_lowpower_type; + +/** + * @brief crm pll clock source + */ +typedef enum +{ + CRM_PLL_SOURCE_HICK = 0x00, /*!< high speed internal clock as pll reference clock source */ + CRM_PLL_SOURCE_HEXT = 0x01 /*!< high speed external crystal as pll reference clock source */ +} crm_pll_clock_source_type; + +/** + * @brief crm pll fr + */ +typedef enum +{ + CRM_PLL_FR_1 = 0x00, /*!< pll post-division div1 */ + CRM_PLL_FR_2 = 0x01, /*!< pll post-division div2 */ + CRM_PLL_FR_4 = 0x02, /*!< pll post-division div4 */ + CRM_PLL_FR_8 = 0x03, /*!< pll post-division div8 */ + CRM_PLL_FR_16 = 0x04, /*!< pll post-division div16 */ + CRM_PLL_FR_32 = 0x05 /*!< pll post-division div32 */ +} crm_pll_fr_type; + +/** + * @brief crm clock source + */ +typedef enum +{ + CRM_CLOCK_SOURCE_HICK = 0x00, /*!< high speed internal clock */ + CRM_CLOCK_SOURCE_HEXT = 0x01, /*!< high speed external crystal */ + CRM_CLOCK_SOURCE_PLL = 0x02, /*!< phase locking loop */ + CRM_CLOCK_SOURCE_LEXT = 0x03, /*!< low speed external crystal */ + CRM_CLOCK_SOURCE_LICK = 0x04 /*!< low speed internal clock */ +} crm_clock_source_type; + +/** + * @brief crm ahb division + */ +typedef enum +{ + CRM_AHB_DIV_1 = 0x00, /*!< sclk div1 to ahbclk */ + CRM_AHB_DIV_2 = 0x08, /*!< sclk div2 to ahbclk */ + CRM_AHB_DIV_4 = 0x09, /*!< sclk div4 to ahbclk */ + CRM_AHB_DIV_8 = 0x0A, /*!< sclk div8 to ahbclk */ + CRM_AHB_DIV_16 = 0x0B, /*!< sclk div16 to ahbclk */ + CRM_AHB_DIV_64 = 0x0C, /*!< sclk div64 to ahbclk */ + CRM_AHB_DIV_128 = 0x0D, /*!< sclk div128 to ahbclk */ + CRM_AHB_DIV_256 = 0x0E, /*!< sclk div256 to ahbclk */ + CRM_AHB_DIV_512 = 0x0F /*!< sclk div512 to ahbclk */ +} crm_ahb_div_type; + +/** + * @brief crm apb1 division + */ +typedef enum +{ + CRM_APB1_DIV_1 = 0x00, /*!< ahbclk div1 to apb1clk */ + CRM_APB1_DIV_2 = 0x04, /*!< ahbclk div2 to apb1clk */ + CRM_APB1_DIV_4 = 0x05, /*!< ahbclk div4 to apb1clk */ + CRM_APB1_DIV_8 = 0x06, /*!< ahbclk div8 to apb1clk */ + CRM_APB1_DIV_16 = 0x07 /*!< ahbclk div16 to apb1clk */ +} crm_apb1_div_type; + +/** + * @brief crm apb2 division + */ +typedef enum +{ + CRM_APB2_DIV_1 = 0x00, /*!< ahbclk div1 to apb2clk */ + CRM_APB2_DIV_2 = 0x04, /*!< ahbclk div2 to apb2clk */ + CRM_APB2_DIV_4 = 0x05, /*!< ahbclk div4 to apb2clk */ + CRM_APB2_DIV_8 = 0x06, /*!< ahbclk div8 to apb2clk */ + CRM_APB2_DIV_16 = 0x07 /*!< ahbclk div16 to apb2clk */ +} crm_apb2_div_type; + +/** + * @brief crm usb division + */ +typedef enum +{ + CRM_USB_DIV_1_5 = 0x00, /*!< pllclk div1.5 to usbclk */ + CRM_USB_DIV_1 = 0x01, /*!< pllclk div1 to usbclk */ + CRM_USB_DIV_2_5 = 0x02, /*!< pllclk div2.5 to usbclk */ + CRM_USB_DIV_2 = 0x03, /*!< pllclk div2 to usbclk */ + CRM_USB_DIV_3_5 = 0x04, /*!< pllclk div3.5 to usbclk */ + CRM_USB_DIV_3 = 0x05, /*!< pllclk div3 to usbclk */ + CRM_USB_DIV_4_5 = 0x06, /*!< pllclk div4.5 to usbclk */ + CRM_USB_DIV_4 = 0x07, /*!< pllclk div4 to usbclk */ + CRM_USB_DIV_5_5 = 0x08, /*!< pllclk div5.5 to usbclk */ + CRM_USB_DIV_5 = 0x09, /*!< pllclk div5 to usbclk */ + CRM_USB_DIV_6_5 = 0x0A, /*!< pllclk div6.5 to usbclk */ + CRM_USB_DIV_6 = 0x0B, /*!< pllclk div6 to usbclk */ + CRM_USB_DIV_7 = 0x0C /*!< pllclk div7 to usbclk */ +} crm_usb_div_type; + +/** + * @brief crm ertc clock + */ +typedef enum +{ + CRM_ERTC_CLOCK_NOCLK = 0x000, /*!< no clock as ertc clock source */ + CRM_ERTC_CLOCK_LEXT = 0x001, /*!< low speed external crystal as ertc clock source */ + CRM_ERTC_CLOCK_LICK = 0x002, /*!< low speed internal clock as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_2 = 0x023, /*!< high speed external crystal div2 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_3 = 0x033, /*!< high speed external crystal div3 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_4 = 0x043, /*!< high speed external crystal div4 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_5 = 0x053, /*!< high speed external crystal div5 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_6 = 0x063, /*!< high speed external crystal div6 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_7 = 0x073, /*!< high speed external crystal div7 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_8 = 0x083, /*!< high speed external crystal div8 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_9 = 0x093, /*!< high speed external crystal div9 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_10 = 0x0A3, /*!< high speed external crystal div10 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_11 = 0x0B3, /*!< high speed external crystal div11 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_12 = 0x0C3, /*!< high speed external crystal div12 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_13 = 0x0D3, /*!< high speed external crystal div13 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_14 = 0x0E3, /*!< high speed external crystal div14 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_15 = 0x0F3, /*!< high speed external crystal div15 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_16 = 0x103, /*!< high speed external crystal div16 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_17 = 0x113, /*!< high speed external crystal div17 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_18 = 0x123, /*!< high speed external crystal div18 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_19 = 0x133, /*!< high speed external crystal div19 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_20 = 0x143, /*!< high speed external crystal div20 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_21 = 0x153, /*!< high speed external crystal div21 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_22 = 0x163, /*!< high speed external crystal div22 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_23 = 0x173, /*!< high speed external crystal div23 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_24 = 0x183, /*!< high speed external crystal div24 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_25 = 0x193, /*!< high speed external crystal div25 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_26 = 0x1A3, /*!< high speed external crystal div26 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_27 = 0x1B3, /*!< high speed external crystal div27 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_28 = 0x1C3, /*!< high speed external crystal div28 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_29 = 0x1D3, /*!< high speed external crystal div29 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_30 = 0x1E3, /*!< high speed external crystal div30 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_31 = 0x1F3 /*!< high speed external crystal div31 as ertc clock source */ +} crm_ertc_clock_type; + +/** + * @brief crm hick 48mhz division + */ +typedef enum +{ + CRM_HICK48_DIV6 = 0x00, /*!< fixed 8 mhz when hick is selected as sclk */ + CRM_HICK48_NODIV = 0x01 /*!< 8 mhz or 48 mhz depend on hickdiv when hick is selected as sclk */ +} crm_hick_div_6_type; + +/** + * @brief crm sclk select + */ +typedef enum +{ + CRM_SCLK_HICK = 0x00, /*!< select high speed internal clock as sclk */ + CRM_SCLK_HEXT = 0x01, /*!< select high speed external crystal as sclk */ + CRM_SCLK_PLL = 0x02 /*!< select phase locking loop clock as sclk */ +} crm_sclk_type; + +/** + * @brief crm clkout index + */ +typedef enum +{ + CRM_CLKOUT_INDEX_1 = 0x00, /*!< clkout1 */ + CRM_CLKOUT_INDEX_2 = 0x01 /*!< clkout2 */ +} crm_clkout_index_type; + +/** + * @brief crm clkout1 select + */ +typedef enum +{ + CRM_CLKOUT1_HICK = 0x00, /*!< output high speed internal clock to clkout1 pin */ + CRM_CLKOUT1_LEXT = 0x01, /*!< output low speed external crystal to clkout1 pin */ + CRM_CLKOUT1_HEXT = 0x02, /*!< output high speed external crystal to clkout1 pin */ + CRM_CLKOUT1_PLL = 0x03 /*!< output phase locking loop clock to clkout1 pin */ +} crm_clkout1_select_type; + +/** + * @brief crm clkout2 select + */ +typedef enum +{ + CRM_CLKOUT2_SCLK = 0x00, /*!< output system clock to clkout2 pin */ + CRM_CLKOUT2_HEXT = 0x02, /*!< output high speed external crystal to clkout2 pin */ + CRM_CLKOUT2_PLL = 0x03, /*!< output phase locking loop clock to clkout2 pin */ + CRM_CLKOUT2_USB = 0x10, /*!< output usbclk to clkout2 pin */ + CRM_CLKOUT2_ADC = 0x11, /*!< output adcclk to clkout2 pin */ + CRM_CLKOUT2_HICK = 0x12, /*!< output high speed internal clock to clkout2 pin */ + CRM_CLKOUT2_LICK = 0x13, /*!< output low speed internal clock to clkout2 pin */ + CRM_CLKOUT2_LEXT = 0x14 /*!< output low speed external crystal to clkout2 pin */ +} crm_clkout2_select_type; + +/** + * @brief crm clkout division1 + */ +typedef enum +{ + CRM_CLKOUT_DIV1_1 = 0x00, /*!< clkout division1 div1 */ + CRM_CLKOUT_DIV1_2 = 0x04, /*!< clkout division1 div2 */ + CRM_CLKOUT_DIV1_3 = 0x05, /*!< clkout division1 div3 */ + CRM_CLKOUT_DIV1_4 = 0x06, /*!< clkout division1 div4 */ + CRM_CLKOUT_DIV1_5 = 0x07 /*!< clkout division1 div5 */ +} crm_clkout_div1_type; + +/** + * @brief crm clkout division2 + */ +typedef enum +{ + CRM_CLKOUT_DIV2_1 = 0x00, /*!< clkout division2 div1 */ + CRM_CLKOUT_DIV2_2 = 0x08, /*!< clkout division2 div2 */ + CRM_CLKOUT_DIV2_4 = 0x09, /*!< clkout division2 div4 */ + CRM_CLKOUT_DIV2_8 = 0x0A, /*!< clkout division2 div8 */ + CRM_CLKOUT_DIV2_16 = 0x0B, /*!< clkout division2 div16 */ + CRM_CLKOUT_DIV2_64 = 0x0C, /*!< clkout division2 div64 */ + CRM_CLKOUT_DIV2_128 = 0x0D, /*!< clkout division2 div128 */ + CRM_CLKOUT_DIV2_256 = 0x0E, /*!< clkout division2 div256 */ + CRM_CLKOUT_DIV2_512 = 0x0F /*!< clkout division2 div512 */ +} crm_clkout_div2_type; + +/** + * @brief crm auto step mode + */ +typedef enum +{ + CRM_AUTO_STEP_MODE_DISABLE = 0x00, /*!< disable auto step mode */ + CRM_AUTO_STEP_MODE_ENABLE = 0x03 /*!< enable auto step mode */ +} crm_auto_step_mode_type; + +/** + * @brief crm usb 48 mhz clock source select + */ +typedef enum +{ + CRM_USB_CLOCK_SOURCE_PLL = 0x00, /*!< select phase locking loop clock as usb clock source */ + CRM_USB_CLOCK_SOURCE_HICK = 0x01 /*!< select high speed internal clock as usb clock source */ +} crm_usb_clock_source_type; + +/** + * @brief crm hick as system clock frequency select + */ +typedef enum +{ + CRM_HICK_SCLK_8MHZ = 0x00, /*!< fixed 8 mhz when hick is selected as sclk */ + CRM_HICK_SCLK_48MHZ = 0x01 /*!< 8 mhz or 48 mhz depend on hickdiv when hick is selected as sclk */ +} crm_hick_sclk_frequency_type; + +/** + * @brief crm emac output pulse width + */ +typedef enum +{ + CRM_EMAC_PULSE_125MS = 0x00, /*!< emac output pulse width 125ms */ + CRM_EMAC_PULSE_1SCLK = 0x01 /*!< emac output pulse width 1 system clock */ +} crm_emac_output_pulse_type; + +/** + * @brief crm clocks freqency structure + */ +typedef struct +{ + uint32_t sclk_freq; /*!< system clock frequency */ + uint32_t ahb_freq; /*!< ahb bus clock frequency */ + uint32_t apb2_freq; /*!< apb2 bus clock frequency */ + uint32_t apb1_freq; /*!< apb1 bus clock frequency */ +} crm_clocks_freq_type; + +/** + * @brief type define crm register all + */ +typedef struct +{ + /** + * @brief crm ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t hicken : 1; /* [0] */ + __IO uint32_t hickstbl : 1; /* [1] */ + __IO uint32_t hicktrim : 6; /* [7:2] */ + __IO uint32_t hickcal : 8; /* [15:8] */ + __IO uint32_t hexten : 1; /* [16] */ + __IO uint32_t hextstbl : 1; /* [17] */ + __IO uint32_t hextbyps : 1; /* [18] */ + __IO uint32_t cfden : 1; /* [19] */ + __IO uint32_t reserved1 : 4; /* [23:20] */ + __IO uint32_t pllen : 1; /* [24] */ + __IO uint32_t pllstbl : 1; /* [25] */ + __IO uint32_t reserved2 : 6; /* [31:26] */ + } ctrl_bit; + }; + + /** + * @brief crm pllcfg register, offset:0x04 + */ + union + { + __IO uint32_t pllcfg; + struct + { + __IO uint32_t pllms : 4; /* [3:0] */ + __IO uint32_t reserved1 : 2; /* [5:4] */ + __IO uint32_t pllns : 9; /* [14:6] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t pllfr : 3; /* [18:16] */ + __IO uint32_t reserved3 : 3; /* [21:19] */ + __IO uint32_t pllrcs : 1; /* [22] */ + __IO uint32_t reserved4 : 9; /* [31:23] */ + } pllcfg_bit; + }; + + /** + * @brief crm cfg register, offset:0x08 + */ + union + { + __IO uint32_t cfg; + struct + { + __IO uint32_t sclksel : 2; /* [1:0] */ + __IO uint32_t sclksts : 2; /* [3:2] */ + __IO uint32_t ahbdiv : 4; /* [7:4] */ + __IO uint32_t reserved1 : 2; /* [9:8] */ + __IO uint32_t apb1div : 3; /* [12:10] */ + __IO uint32_t apb2div : 3; /* [15:13] */ + __IO uint32_t ertcdiv : 5; /* [20:16] */ + __IO uint32_t clkout1_sel : 2; /* [22:21] */ + __IO uint32_t reserved2 : 1; /* [23] */ + __IO uint32_t clkout1div1 : 3; /* [26:24] */ + __IO uint32_t clkout2div1 : 3; /* [29:27] */ + __IO uint32_t clkout2_sel1 : 2; /* [31:30] */ + } cfg_bit; + }; + + /** + * @brief crm clkint register, offset:0x0C + */ + union + { + __IO uint32_t clkint; + struct + { + __IO uint32_t lickstblf : 1; /* [0] */ + __IO uint32_t lextstblf : 1; /* [1] */ + __IO uint32_t hickstblf : 1; /* [2] */ + __IO uint32_t hextstblf : 1; /* [3] */ + __IO uint32_t pllstblf : 1; /* [4] */ + __IO uint32_t reserved1 : 2; /* [6:5] */ + __IO uint32_t cfdf : 1; /* [7] */ + __IO uint32_t lickstblien : 1; /* [8] */ + __IO uint32_t lextstblien : 1; /* [9] */ + __IO uint32_t hickstblien : 1; /* [10] */ + __IO uint32_t hextstblien : 1; /* [11] */ + __IO uint32_t pllstblien : 1; /* [12] */ + __IO uint32_t reserved2 : 3; /* [15:13] */ + __IO uint32_t lickstblfc : 1; /* [16] */ + __IO uint32_t lextstblfc : 1; /* [17] */ + __IO uint32_t hickstblfc : 1; /* [18] */ + __IO uint32_t hextstblfc : 1; /* [19] */ + __IO uint32_t pllstblfc : 1; /* [20] */ + __IO uint32_t reserved3 : 2; /* [22:21] */ + __IO uint32_t cfdfc : 1; /* [23] */ + __IO uint32_t reserved4 : 8; /* [31:24] */ + } clkint_bit; + }; + + /** + * @brief crm ahbrst1 register, offset:0x10 + */ + union + { + __IO uint32_t ahbrst1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioarst : 1; /* [0] */ + __IO uint32_t gpiobrst : 1; /* [1] */ + __IO uint32_t gpiocrst : 1; /* [2] */ + __IO uint32_t gpiodrst : 1; /* [3] */ + __IO uint32_t gpioerst : 1; /* [4] */ + __IO uint32_t gpiofrst : 1; /* [5] */ + __IO uint32_t gpiogrst : 1; /* [6] */ + __IO uint32_t gpiohrst : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcrst : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmarst : 1; /* [21] */ + __IO uint32_t dma1rst : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2rst : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2rst : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahbrst1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioarst : 1; /* [0] */ + __IO uint32_t gpiobrst : 1; /* [1] */ + __IO uint32_t gpiocrst : 1; /* [2] */ + __IO uint32_t gpiodrst : 1; /* [3] */ + __IO uint32_t gpioerst : 1; /* [4] */ + __IO uint32_t gpiofrst : 1; /* [5] */ + __IO uint32_t gpiogrst : 1; /* [6] */ + __IO uint32_t gpiohrst : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcrst : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmarst : 1; /* [21] */ + __IO uint32_t dma1rst : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2rst : 1; /* [24] */ + __IO uint32_t emacrst : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2rst : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahbrst1_bit; +#endif + }; + + /** + * @brief crm ahbrst2 register, offset:0x14 + */ + union + { + __IO uint32_t ahbrst2; + struct + { + __IO uint32_t dvprst : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1rst : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1rst : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahbrst2_bit; + }; + + /** + * @brief crm ahbrst3 register, offset:0x18 + */ + union + { + __IO uint32_t ahbrst3; + struct + { + __IO uint32_t xmcrst : 1; /* [0] */ + __IO uint32_t qspi1rst : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2rst : 1; /* [14] */ + __IO uint32_t sdio2rst : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahbrst3_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x1C + */ + __IO uint32_t reserved1; + + /** + * @brief crm apb1rst register, offset:0x20 + */ + union + { + __IO uint32_t apb1rst; + struct + { + __IO uint32_t tmr2rst : 1; /* [0] */ + __IO uint32_t tmr3rst : 1; /* [1] */ + __IO uint32_t tmr4rst : 1; /* [2] */ + __IO uint32_t tmr5rst : 1; /* [3] */ + __IO uint32_t tmr6rst : 1; /* [4] */ + __IO uint32_t tmr7rst : 1; /* [5] */ + __IO uint32_t tmr12rst : 1; /* [6] */ + __IO uint32_t tmr13rst : 1; /* [7] */ + __IO uint32_t adc14rst : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdtrst : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2rst : 1; /* [14] */ + __IO uint32_t spi3rst : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2rst : 1; /* [17] */ + __IO uint32_t usart3rst : 1; /* [18] */ + __IO uint32_t uart4rst : 1; /* [19] */ + __IO uint32_t uart5rst : 1; /* [20] */ + __IO uint32_t i2c1rst : 1; /* [21] */ + __IO uint32_t i2c2rst : 1; /* [22] */ + __IO uint32_t i2c3rst : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1rst : 1; /* [25] */ + __IO uint32_t can2rst : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwcrst : 1; /* [28] */ + __IO uint32_t dacrst : 1; /* [29] */ + __IO uint32_t uart7rst : 1; /* [30] */ + __IO uint32_t uart8rst : 1; /* [31] */ + } apb1rst_bit; + }; + + /** + * @brief crm apb2rst register, offset:0x24 + */ + union + { + __IO uint32_t apb2rst; + struct + { + __IO uint32_t tmr1rst : 1; /* [0] */ + __IO uint32_t tmr8rst : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1rst : 1; /* [4] */ + __IO uint32_t usart6rst : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adcrst : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1rst : 1; /* [12] */ + __IO uint32_t spi4rst : 1; /* [13] */ + __IO uint32_t scfgrst : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9rst : 1; /* [16] */ + __IO uint32_t tmr10rst : 1; /* [17] */ + __IO uint32_t tmr11rst : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20rst : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t accrst : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2rst_bit; + }; + + /** + * @brief crm reserved2 register, offset:0x28~0x2C + */ + __IO uint32_t reserved2[2]; + + /** + * @brief crm ahben1 register, offset:0x30 + */ + union + { + __IO uint32_t ahben1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioaen : 1; /* [0] */ + __IO uint32_t gpioben : 1; /* [1] */ + __IO uint32_t gpiocen : 1; /* [2] */ + __IO uint32_t gpioden : 1; /* [3] */ + __IO uint32_t gpioeen : 1; /* [4] */ + __IO uint32_t gpiofen : 1; /* [5] */ + __IO uint32_t gpiogen : 1; /* [6] */ + __IO uint32_t gpiohen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmaen : 1; /* [21] */ + __IO uint32_t dma1en : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2en : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2en : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahben1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioaen : 1; /* [0] */ + __IO uint32_t gpioben : 1; /* [1] */ + __IO uint32_t gpiocen : 1; /* [2] */ + __IO uint32_t gpioden : 1; /* [3] */ + __IO uint32_t gpioeen : 1; /* [4] */ + __IO uint32_t gpiofen : 1; /* [5] */ + __IO uint32_t gpiogen : 1; /* [6] */ + __IO uint32_t gpiohen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmaen : 1; /* [21] */ + __IO uint32_t dma1en : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2en : 1; /* [24] */ + __IO uint32_t emacen : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2en : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahben1_bit; +#endif + }; + + /** + * @brief crm ahben2 register, offset:0x34 + */ + union + { + __IO uint32_t ahben2; + struct + { + __IO uint32_t dvpen : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1en : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahben2_bit; + }; + + /** + * @brief crm ahben3 register, offset:0x38 + */ + union + { + __IO uint32_t ahben3; + struct + { + __IO uint32_t xmcen : 1; /* [0] */ + __IO uint32_t qspi1en : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2en : 1; /* [14] */ + __IO uint32_t sdio2en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahben3_bit; + }; + + /** + * @brief crm reserved3 register, offset:0x3C + */ + __IO uint32_t reserved3; + + /** + * @brief crm apb1en register, offset:0x40 + */ + union + { + __IO uint32_t apb1en; + struct + { + __IO uint32_t tmr2en : 1; /* [0] */ + __IO uint32_t tmr3en : 1; /* [1] */ + __IO uint32_t tmr4en : 1; /* [2] */ + __IO uint32_t tmr5en : 1; /* [3] */ + __IO uint32_t tmr6en : 1; /* [4] */ + __IO uint32_t tmr7en : 1; /* [5] */ + __IO uint32_t tmr12en : 1; /* [6] */ + __IO uint32_t tmr13en : 1; /* [7] */ + __IO uint32_t adc14en : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdten : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2en : 1; /* [14] */ + __IO uint32_t spi3en : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2en : 1; /* [17] */ + __IO uint32_t usart3en : 1; /* [18] */ + __IO uint32_t uart4en : 1; /* [19] */ + __IO uint32_t uart5en : 1; /* [20] */ + __IO uint32_t i2c1en : 1; /* [21] */ + __IO uint32_t i2c2en : 1; /* [22] */ + __IO uint32_t i2c3en : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1en : 1; /* [25] */ + __IO uint32_t can2en : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwcen : 1; /* [28] */ + __IO uint32_t dacen : 1; /* [29] */ + __IO uint32_t uart7en : 1; /* [30] */ + __IO uint32_t uart8en : 1; /* [31] */ + } apb1en_bit; + }; + + /** + * @brief crm apb2en register, offset:0x44 + */ + union + { + __IO uint32_t apb2en; + struct + { + __IO uint32_t tmr1en : 1; /* [0] */ + __IO uint32_t tmr8en : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1en : 1; /* [4] */ + __IO uint32_t usart6en : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adcen : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1en : 1; /* [12] */ + __IO uint32_t spi4en : 1; /* [13] */ + __IO uint32_t scfgen : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9en : 1; /* [16] */ + __IO uint32_t tmr10en : 1; /* [17] */ + __IO uint32_t tmr11en : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20en : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t accen : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2en_bit; + }; + + /** + * @brief crm reserved4 register, offset:0x48~0x4C + */ + __IO uint32_t reserved4[2]; + + /** + * @brief crm ahblpen1 register, offset:0x50 + */ + union + { + __IO uint32_t ahblpen1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioalpen : 1; /* [0] */ + __IO uint32_t gpioblpen : 1; /* [1] */ + __IO uint32_t gpioclpen : 1; /* [2] */ + __IO uint32_t gpiodlpen : 1; /* [3] */ + __IO uint32_t gpioelpen : 1; /* [4] */ + __IO uint32_t gpioflpen : 1; /* [5] */ + __IO uint32_t gpioglpen : 1; /* [6] */ + __IO uint32_t gpiohlpen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crclpen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmalpen : 1; /* [21] */ + __IO uint32_t dma1lpen : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2lpen : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2lpen : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahblpen1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioalpen : 1; /* [0] */ + __IO uint32_t gpioblpen : 1; /* [1] */ + __IO uint32_t gpioclpen : 1; /* [2] */ + __IO uint32_t gpiodlpen : 1; /* [3] */ + __IO uint32_t gpioelpen : 1; /* [4] */ + __IO uint32_t gpioflpen : 1; /* [5] */ + __IO uint32_t gpioglpen : 1; /* [6] */ + __IO uint32_t gpiohlpen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crclpen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmalpen : 1; /* [21] */ + __IO uint32_t dma1lpen : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2lpen : 1; /* [24] */ + __IO uint32_t emaclpen : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2lpen : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahblpen1_bit; +#endif + }; + + /** + * @brief crm ahblpen2 register, offset:0x54 + */ + union + { + __IO uint32_t ahblpen2; + struct + { + __IO uint32_t dvplpen : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1lpen : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahblpen2_bit; + }; + + /** + * @brief crm ahblpen3 register, offset:0x58 + */ + union + { + __IO uint32_t ahblpen3; + struct + { + __IO uint32_t xmclpen : 1; /* [0] */ + __IO uint32_t qspi1lpen : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2lpen : 1; /* [14] */ + __IO uint32_t sdio2lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahblpen3_bit; + }; + + /** + * @brief crm reserved5 register, offset:0x5C + */ + __IO uint32_t reserved5; + + /** + * @brief crm apb1lpen register, offset:0x60 + */ + union + { + __IO uint32_t apb1lpen; + struct + { + __IO uint32_t tmr2lpen : 1; /* [0] */ + __IO uint32_t tmr3lpen : 1; /* [1] */ + __IO uint32_t tmr4lpen : 1; /* [2] */ + __IO uint32_t tmr5lpen : 1; /* [3] */ + __IO uint32_t tmr6lpen : 1; /* [4] */ + __IO uint32_t tmr7lpen : 1; /* [5] */ + __IO uint32_t tmr12lpen : 1; /* [6] */ + __IO uint32_t tmr13lpen : 1; /* [7] */ + __IO uint32_t adc14lpen : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdtlpen : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2lpen : 1; /* [14] */ + __IO uint32_t spi3lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2lpen : 1; /* [17] */ + __IO uint32_t usart3lpen : 1; /* [18] */ + __IO uint32_t uart4lpen : 1; /* [19] */ + __IO uint32_t uart5lpen : 1; /* [20] */ + __IO uint32_t i2c1lpen : 1; /* [21] */ + __IO uint32_t i2c2lpen : 1; /* [22] */ + __IO uint32_t i2c3lpen : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1lpen : 1; /* [25] */ + __IO uint32_t can2lpen : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwclpen : 1; /* [28] */ + __IO uint32_t daclpen : 1; /* [29] */ + __IO uint32_t uart7lpen : 1; /* [30] */ + __IO uint32_t uart8lpen : 1; /* [31] */ + } apb1lpen_bit; + }; + + /** + * @brief crm apb2lpen register, offset:0x64 + */ + union + { + __IO uint32_t apb2lpen; + struct + { + __IO uint32_t tmr1lpen : 1; /* [0] */ + __IO uint32_t tmr8lpen : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1lpen : 1; /* [4] */ + __IO uint32_t usart6lpen : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adclpen : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1lpen : 1; /* [12] */ + __IO uint32_t spi4lpen : 1; /* [13] */ + __IO uint32_t scfglpen : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9lpen : 1; /* [16] */ + __IO uint32_t tmr10lpen : 1; /* [17] */ + __IO uint32_t tmr11lpen : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20lpen : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t acclpen : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2lpen_bit; + }; + + /** + * @brief crm reserved6 register, offset:0x68~0x6C + */ + __IO uint32_t reserved6[2]; + + /** + * @brief crm bpdc register, offset:0x70 + */ + union + { + __IO uint32_t bpdc; + struct + { + __IO uint32_t lexten : 1; /* [0] */ + __IO uint32_t lextstbl : 1; /* [1] */ + __IO uint32_t lextbyps : 1; /* [2] */ + __IO uint32_t reserved1 : 5; /* [7:3] */ + __IO uint32_t ertcsel : 2; /* [9:8] */ + __IO uint32_t reserved2 : 5; /* [14:10] */ + __IO uint32_t ertcen : 1; /* [15] */ + __IO uint32_t bpdrst : 1; /* [16] */ + __IO uint32_t reserved3 : 15;/* [31:17] */ + } bpdc_bit; + }; + + /** + * @brief crm ctrlsts register, offset:0x74 + */ + union + { + __IO uint32_t ctrlsts; + struct + { + __IO uint32_t licken : 1; /* [0] */ + __IO uint32_t lickstbl : 1; /* [1] */ + __IO uint32_t reserved1 : 22;/* [23:2] */ + __IO uint32_t rstfc : 1; /* [24] */ + __IO uint32_t reserved2 : 1; /* [25] */ + __IO uint32_t nrstf : 1; /* [26] */ + __IO uint32_t porrstf : 1; /* [27] */ + __IO uint32_t swrstf : 1; /* [28] */ + __IO uint32_t wdtrstf : 1; /* [29] */ + __IO uint32_t wwdtrstf : 1; /* [30] */ + __IO uint32_t lprstf : 1; /* [31] */ + } ctrlsts_bit; + }; + + /** + * @brief crm reserved7 register, offset:0x78~0x9C + */ + __IO uint32_t reserved7[10]; + + /** + * @brief crm misc1 register, offset:0xA0 + */ + union + { + __IO uint32_t misc1; + struct + { + __IO uint32_t hickcal_key : 8; /* [7:0] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t hickdiv : 1; /* [12] */ + __IO uint32_t hick_to_usb : 1; /* [13] */ + __IO uint32_t hick_to_sclk : 1; /* [14] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t clkout2_sel2 : 4; /* [19:16] */ + __IO uint32_t reserved3 : 4; /* [23:20] */ + __IO uint32_t clkout1div2 : 4; /* [27:24] */ + __IO uint32_t clkout2div2 : 4; /* [31:28] */ + } misc1_bit; + }; + + /** + * @brief crm misc2 register, offset:0xA4 + */ + union + { + __IO uint32_t misc2; + struct + { + __IO uint32_t reserved1 : 4; /* [3:0] */ + __IO uint32_t auto_step_en : 2; /* [5:4] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t clk_to_tmr : 1; /* [8] */ + __IO uint32_t emac_pps_sel : 1; /* [9] */ + __IO uint32_t reserved3 : 2; /* [11:10] */ + __IO uint32_t usbdiv : 4; /* [15:12] */ + __IO uint32_t reserved4 : 16;/* [31:16] */ + } misc2_bit; + }; + +} crm_type; + +/** + * @} + */ + +#define CRM ((crm_type *) CRM_BASE) + +/** @defgroup CRM_exported_functions + * @{ + */ + +void crm_reset(void); +void crm_lext_bypass(confirm_state new_state); +void crm_hext_bypass(confirm_state new_state); +flag_status crm_flag_get(uint32_t flag); +error_status crm_hext_stable_wait(void); +void crm_hick_clock_trimming_set(uint8_t trim_value); +void crm_hick_clock_calibration_set(uint8_t cali_value); +void crm_periph_clock_enable(crm_periph_clock_type value, confirm_state new_state); +void crm_periph_reset(crm_periph_reset_type value, confirm_state new_state); +void crm_periph_lowpower_mode_enable(crm_periph_clock_lowpower_type value, confirm_state new_state); +void crm_clock_source_enable(crm_clock_source_type source, confirm_state new_state); +void crm_flag_clear(uint32_t flag); +void crm_ertc_clock_select(crm_ertc_clock_type value); +void crm_ertc_clock_enable(confirm_state new_state); +void crm_ahb_div_set(crm_ahb_div_type value); +void crm_apb1_div_set(crm_apb1_div_type value); +void crm_apb2_div_set(crm_apb2_div_type value); +void crm_usb_clock_div_set(crm_usb_div_type value); +void crm_clock_failure_detection_enable(confirm_state new_state); +void crm_battery_powered_domain_reset(confirm_state new_state); +void crm_auto_step_mode_enable(confirm_state new_state); +void crm_hick_divider_select(crm_hick_div_6_type value); +void crm_hick_sclk_frequency_select(crm_hick_sclk_frequency_type value); +void crm_usb_clock_source_select(crm_usb_clock_source_type value); +void crm_clkout_to_tmr10_enable(confirm_state new_state); +void crm_pll_config(crm_pll_clock_source_type clock_source, uint16_t pll_ns, \ + uint16_t pll_ms, crm_pll_fr_type pll_fr); +void crm_sysclk_switch(crm_sclk_type value); +crm_sclk_type crm_sysclk_switch_status_get(void); +void crm_clocks_freq_get(crm_clocks_freq_type *clocks_struct); +void crm_clock_out1_set(crm_clkout1_select_type clkout); +void crm_clock_out2_set(crm_clkout2_select_type clkout); +void crm_clkout_div_set(crm_clkout_index_type index, crm_clkout_div1_type div1, crm_clkout_div2_type div2); +void crm_emac_output_pulse_set(crm_emac_output_pulse_type width); +void crm_interrupt_enable(uint32_t crm_int, confirm_state new_state); +error_status crm_pll_parameter_calculate(crm_pll_clock_source_type pll_rcs, uint32_t target_sclk_freq, \ + uint16_t *ret_ms, uint16_t *ret_ns, uint16_t *ret_fr); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h new file mode 100644 index 0000000000..4b0e944252 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h @@ -0,0 +1,394 @@ +/** + ************************************************************************** + * @file at32f435_437_dac.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 dac header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_DAC_H +#define __AT32F435_437_DAC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +#define DAC1_D1DMAUDRF ((uint32_t)(0x00002000)) +#define DAC2_D2DMAUDRF ((uint32_t)(0x20000000)) + +/** @defgroup DAC_exported_types + * @{ + */ + +/** + * @brief dac select type + */ +typedef enum +{ + DAC1_SELECT = 0x01, /*!< dac1 select */ + DAC2_SELECT = 0x02 /*!< dac2 select */ +} dac_select_type; + +/** + * @brief dac trigger type + */ +typedef enum +{ + DAC_TMR6_TRGOUT_EVENT = 0x00, /*!< dac trigger selection:timer6 trgout event */ + DAC_TMR8_TRGOUT_EVENT = 0x01, /*!< dac trigger selection:timer8 trgout event */ + DAC_TMR7_TRGOUT_EVENT = 0x02, /*!< dac trigger selection:timer7 trgout event */ + DAC_TMR5_TRGOUT_EVENT = 0x03, /*!< dac trigger selection:timer5 trgout event */ + DAC_TMR2_TRGOUT_EVENT = 0x04, /*!< dac trigger selection:timer2 trgout event */ + DAC_TMR4_TRGOUT_EVENT = 0x05, /*!< dac trigger selection:timer4 trgout event */ + DAC_EXTERNAL_INTERRUPT_LINE_9 = 0x06, /*!< dac trigger selection:external line9 */ + DAC_SOFTWARE_TRIGGER = 0x07 /*!< dac trigger selection:software trigger */ +} dac_trigger_type; + +/** + * @brief dac wave type + */ +typedef enum +{ + DAC_WAVE_GENERATE_NONE = 0x00, /*!< dac wave generation disabled */ + DAC_WAVE_GENERATE_NOISE = 0x01, /*!< dac noise wave generation enabled */ + DAC_WAVE_GENERATE_TRIANGLE = 0x02 /*!< dac triangle wave generation enabled */ +} dac_wave_type; + +/** + * @brief dac mask amplitude type + */ +typedef enum +{ + DAC_LSFR_BIT0_AMPLITUDE_1 = 0x00, /*!< unmask bit0/ triangle amplitude equal to 1 */ + DAC_LSFR_BIT10_AMPLITUDE_3 = 0x01, /*!< unmask bit[1:0]/ triangle amplitude equal to 3 */ + DAC_LSFR_BIT20_AMPLITUDE_7 = 0x02, /*!< unmask bit[2:0]/ triangle amplitude equal to 7 */ + DAC_LSFR_BIT30_AMPLITUDE_15 = 0x03, /*!< unmask bit[3:0]/ triangle amplitude equal to 15 */ + DAC_LSFR_BIT40_AMPLITUDE_31 = 0x04, /*!< unmask bit[4:0]/ triangle amplitude equal to 31 */ + DAC_LSFR_BIT50_AMPLITUDE_63 = 0x05, /*!< unmask bit[5:0]/ triangle amplitude equal to 63 */ + DAC_LSFR_BIT60_AMPLITUDE_127 = 0x06, /*!< unmask bit[6:0]/ triangle amplitude equal to 127 */ + DAC_LSFR_BIT70_AMPLITUDE_255 = 0x07, /*!< unmask bit[7:0]/ triangle amplitude equal to 255 */ + DAC_LSFR_BIT80_AMPLITUDE_511 = 0x08, /*!< unmask bit[8:0]/ triangle amplitude equal to 511 */ + DAC_LSFR_BIT90_AMPLITUDE_1023 = 0x09, /*!< unmask bit[9:0]/ triangle amplitude equal to 1023 */ + DAC_LSFR_BITA0_AMPLITUDE_2047 = 0x0A, /*!< unmask bit[10:0]/ triangle amplitude equal to 2047 */ + DAC_LSFR_BITB0_AMPLITUDE_4095 = 0x0B /*!< unmask bit[11:0]/ triangle amplitude equal to 4095 */ +} dac_mask_amplitude_type; + +/** + * @brief dac1 aligned data type + */ +typedef enum +{ + DAC1_12BIT_RIGHT = 0x40007408, /*!< dac1 12-bit data right-aligned */ + DAC1_12BIT_LEFT = 0x4000740C, /*!< dac1 12-bit data left-aligned */ + DAC1_8BIT_RIGHT = 0x40007410 /*!< dac1 8-bit data right-aligned */ +} dac1_aligned_data_type; + +/** + * @brief dac2 aligned data type + */ +typedef enum +{ + DAC2_12BIT_RIGHT = 0x40007414, /*!< dac2 12-bit data right-aligned */ + DAC2_12BIT_LEFT = 0x40007418, /*!< dac2 12-bit data left-aligned */ + DAC2_8BIT_RIGHT = 0x4000741C /*!< dac2 8-bit data right-aligned */ +} dac2_aligned_data_type; + +/** + * @brief dac dual data type + */ +typedef enum +{ + DAC_DUAL_12BIT_RIGHT = 0x40007420, /*!divr_bit.fdiv = div) + +/** + * @} + */ + +/** @defgroup FLASH_exported_types + * @{ + */ + +/** + * @brief flash usd eopb0 type + */ +typedef enum +{ + FLASH_EOPB0_SRAM_512K = 0x00, /*!< sram 512k, flash zw area 128k */ + FLASH_EOPB0_SRAM_448K = 0x01, /*!< sram 448k, flash zw area 192k */ + FLASH_EOPB0_SRAM_384K = 0x02, /*!< sram 384k, flash zw area 256k */ + FLASH_EOPB0_SRAM_320K = 0x03, /*!< sram 320k, flash zw area 320k */ + FLASH_EOPB0_SRAM_256K = 0x04, /*!< sram 256k, flash zw area 384k */ + FLASH_EOPB0_SRAM_192K = 0x05, /*!< sram 192k, flash zw area 448k */ + FLASH_EOPB0_SRAM_128K = 0x06 /*!< sram 128k, flash zw area 512k */ +} flash_usd_eopb0_type; + +/** + * @brief flash clock divider type + */ +typedef enum +{ + FLASH_CLOCK_DIV_2 = 0x00, /*!< flash clock divide by 2 */ + FLASH_CLOCK_DIV_3 = 0x01, /*!< flash clock divide by 3 */ + FLASH_CLOCK_DIV_4 = 0x02 /*!< flash clock divide by 4 */ +} flash_clock_divider_type; + +/** + * @brief flash status type + */ +typedef enum +{ + FLASH_OPERATE_BUSY = 0x00, /*!< flash status is operate busy */ + FLASH_PROGRAM_ERROR = 0x01, /*!< flash status is program error */ + FLASH_EPP_ERROR = 0x02, /*!< flash status is epp error */ + FLASH_OPERATE_DONE = 0x03, /*!< flash status is operate done */ + FLASH_OPERATE_TIMEOUT = 0x04 /*!< flash status is operate timeout */ +} flash_status_type; + +/** + * @brief type define flash register all + */ +typedef struct +{ + /** + * @brief flash psr register, offset:0x00 + */ + union + { + __IO uint32_t psr; + struct + { + __IO uint32_t reserved1 : 12;/* [11:0] */ + __IO uint32_t nzw_bst : 1; /* [12] */ + __IO uint32_t nzw_bst_sts : 1; /* [13] */ + __IO uint32_t reserved2 : 18;/* [31:14] */ + } psr_bit; + }; + + /** + * @brief flash unlock register, offset:0x04 + */ + union + { + __IO uint32_t unlock; + struct + { + __IO uint32_t ukval : 32;/* [31:0] */ + } unlock_bit; + }; + + /** + * @brief flash usd unlock register, offset:0x08 + */ + union + { + __IO uint32_t usd_unlock; + struct + { + __IO uint32_t usd_ukval : 32;/* [31:0] */ + } usd_unlock_bit; + }; + + /** + * @brief flash sts register, offset:0x0C + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t obf : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t prgmerr : 1; /* [2] */ + __IO uint32_t reserved2 : 1; /* [3] */ + __IO uint32_t epperr : 1; /* [4] */ + __IO uint32_t odf : 1; /* [5] */ + __IO uint32_t reserved3 : 26;/* [31:6] */ + } sts_bit; + }; + + /** + * @brief flash ctrl register, offset:0x10 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t fprgm : 1; /* [0] */ + __IO uint32_t secers : 1; /* [1] */ + __IO uint32_t bankers : 1; /* [2] */ + __IO uint32_t blkers : 1; /* [3] */ + __IO uint32_t usdprgm : 1; /* [4] */ + __IO uint32_t usders : 1; /* [5] */ + __IO uint32_t erstr : 1; /* [6] */ + __IO uint32_t oplk : 1; /* [7] */ + __IO uint32_t reserved1 : 1; /* [8] */ + __IO uint32_t usdulks : 1; /* [9] */ + __IO uint32_t errie : 1; /* [10] */ + __IO uint32_t reserved2 : 1; /* [11] */ + __IO uint32_t odfie : 1; /* [12] */ + __IO uint32_t reserved3 : 19;/* [31:13] */ + } ctrl_bit; + }; + + /** + * @brief flash addr register, offset:0x14 + */ + union + { + __IO uint32_t addr; + struct + { + __IO uint32_t fa : 32;/* [31:0] */ + } addr_bit; + }; + + /** + * @brief flash reserved1 register, offset:0x18 + */ + __IO uint32_t reserved1; + + /** + * @brief flash usd register, offset:0x1C + */ + union + { + __IO uint32_t usd; + struct + { + __IO uint32_t usderr : 1; /* [0] */ + __IO uint32_t fap : 1; /* [1] */ + __IO uint32_t wdt_ato_en : 1; /* [2] */ + __IO uint32_t depslp_rst : 1; /* [3] */ + __IO uint32_t stdby_rst : 1; /* [4] */ + __IO uint32_t btopt : 1; /* [5] */ + __IO uint32_t reserved1 : 1; /* [6] */ + __IO uint32_t wdt_depslp : 1; /* [7] */ + __IO uint32_t wdt_stdby : 1; /* [8] */ + __IO uint32_t reserved2 : 1; /* [9] */ + __IO uint32_t user_d0 : 8; /* [17:10] */ + __IO uint32_t user_d1 : 8; /* [25:18] */ + __IO uint32_t reserved3 : 6; /* [31:26] */ + } usd_bit; + }; + + /** + * @brief flash epps0 register, offset:0x20 + */ + union + { + __IO uint32_t epps0; + struct + { + __IO uint32_t epps : 32;/* [31:0] */ + } epps0_bit; + }; + + /** + * @brief flash reserved2 register, offset:0x28~0x24 + */ + __IO uint32_t reserved2[2]; + + /** + * @brief flash epps1 register, offset:0x2C + */ + union + { + __IO uint32_t epps1; + struct + { + __IO uint32_t epps : 32;/* [31:0] */ + } epps1_bit; + }; + + /** + * @brief flash reserved3 register, offset:0x40~0x30 + */ + __IO uint32_t reserved3[5]; + + /** + * @brief flash unlock2 register, offset:0x44 + */ + union + { + __IO uint32_t unlock2; + struct + { + __IO uint32_t ukval : 32;/* [31:0] */ + } unlock2_bit; + }; + + /** + * @brief flash reserved4 register, offset:0x48 + */ + __IO uint32_t reserved4; + + /** + * @brief flash sts2 register, offset:0x4C + */ + union + { + __IO uint32_t sts2; + struct + { + __IO uint32_t obf : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t prgmerr : 1; /* [2] */ + __IO uint32_t reserved2 : 1; /* [3] */ + __IO uint32_t epperr : 1; /* [4] */ + __IO uint32_t odf : 1; /* [5] */ + __IO uint32_t reserved3 : 26;/* [31:6] */ + } sts2_bit; + }; + + /** + * @brief flash ctrl2 register, offset:0x50 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t fprgm : 1; /* [0] */ + __IO uint32_t secers : 1; /* [1] */ + __IO uint32_t bankers : 1; /* [2] */ + __IO uint32_t blkers : 1; /* [3] */ + __IO uint32_t reserved1 : 2; /* [5:4] */ + __IO uint32_t erstr : 1; /* [6] */ + __IO uint32_t oplk : 1; /* [7] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t errie : 1; /* [10] */ + __IO uint32_t reserved3 : 1; /* [11] */ + __IO uint32_t odfie : 1; /* [12] */ + __IO uint32_t reserved4 : 19;/* [31:13] */ + } ctrl2_bit; + }; + + /** + * @brief flash addr2 register, offset:0x54 + */ + union + { + __IO uint32_t addr2; + struct + { + __IO uint32_t fa : 32;/* [31:0] */ + } addr2_bit; + }; + + /** + * @brief flash contr register, offset:0x58 + */ + union + { + __IO uint32_t contr; + struct + { + __IO uint32_t reserved1 : 31;/* [30:0] */ + __IO uint32_t fcontr_en : 1; /* [31] */ + } contr_bit; + }; + + /** + * @brief flash reserved5 register, offset:0x5C + */ + __IO uint32_t reserved5; + + /** + * @brief flash divr register, offset:0x60 + */ + union + { + __IO uint32_t divr; + struct + { + __IO uint32_t fdiv : 2; /* [1:0] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t fdiv_sts : 2; /* [5:4] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } divr_bit; + }; + + /** + * @brief flash reserved6 register, offset:0xC4~0x64 + */ + __IO uint32_t reserved6[25]; + + /** + * @brief flash slib_sts2 register, offset:0xC8 + */ + union + { + __IO uint32_t slib_sts2; + struct + { + __IO uint32_t slib_inst_ss : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } slib_sts2_bit; + }; + + /** + * @brief flash slib_sts0 register, offset:0xCC + */ + union + { + __IO uint32_t slib_sts0; + struct + { + __IO uint32_t reserved1 : 3; /* [2:0] */ + __IO uint32_t slib_enf : 1; /* [3] */ + __IO uint32_t reserved2 : 28;/* [31:4] */ + } slib_sts0_bit; + }; + + /** + * @brief flash slib_sts1 register, offset:0xD0 + */ + union + { + __IO uint32_t slib_sts1; + struct + { + __IO uint32_t slib_ss : 16;/* [15:0] */ + __IO uint32_t slib_es : 16;/* [31:16] */ + } slib_sts1_bit; + }; + + /** + * @brief flash slib_pwd_clr register, offset:0xD4 + */ + union + { + __IO uint32_t slib_pwd_clr; + struct + { + __IO uint32_t slib_pclr_val : 32;/* [31:0] */ + } slib_pwd_clr_bit; + }; + + /** + * @brief flash slib_misc_sts register, offset:0xD8 + */ + union + { + __IO uint32_t slib_misc_sts; + struct + { + __IO uint32_t slib_pwd_err : 1; /* [0] */ + __IO uint32_t slib_pwd_ok : 1; /* [1] */ + __IO uint32_t slib_ulkf : 1; /* [2] */ + __IO uint32_t reserved1 : 13;/* [15:3] */ + __IO uint32_t slib_rcnt : 9; /* [24:16] */ + __IO uint32_t reserved2 : 7; /* [31:25] */ + } slib_misc_sts_bit; + }; + + /** + * @brief flash slib_set_pwd register, offset:0xDC + */ + union + { + __IO uint32_t slib_set_pwd; + struct + { + __IO uint32_t slib_pset_val : 32;/* [31:0] */ + } slib_set_pwd_bit; + }; + + /** + * @brief flash slib_set_range0 register, offset:0xE0 + */ + union + { + __IO uint32_t slib_set_range0; + struct + { + __IO uint32_t slib_ss_set : 16;/* [15:0] */ + __IO uint32_t slib_es_set : 16;/* [31:16] */ + } slib_set_range0_bit; + }; + + /** + * @brief flash slib_set_range1 register, offset:0xE4 + */ + union + { + __IO uint32_t slib_set_range1; + struct + { + __IO uint32_t slib_iss_set : 16;/* [15:0] */ + __IO uint32_t reserved1 : 15;/* [30:16] */ + __IO uint32_t set_slib_strt : 1; /* [31] */ + } slib_set_range1_bit; + }; + + /** + * @brief flash reserved7 register, offset:0xEC~0xE8 + */ + __IO uint32_t reserved7[2]; + + /** + * @brief flash slib_unlock register, offset:0xF0 + */ + union + { + __IO uint32_t slib_unlock; + struct + { + __IO uint32_t slib_ukval : 32;/* [31:0] */ + } slib_unlock_bit; + }; + + /** + * @brief flash crc_ctrl register, offset:0xF4 + */ + union + { + __IO uint32_t crc_ctrl; + struct + { + __IO uint32_t crc_ss : 12;/* [11:0] */ + __IO uint32_t crc_sn : 12;/* [23:12] */ + __IO uint32_t reserved1 : 7; /* [30:24] */ + __IO uint32_t crc_strt : 1; /* [31] */ + } crc_ctrl_bit; + }; + + /** + * @brief flash crc_chkr register, offset:0xF8 + */ + union + { + __IO uint32_t crc_chkr; + struct + { + __IO uint32_t crc_chkr : 32;/* [31:0] */ + } crc_chkr_bit; + }; + +} flash_type; + +/** + * @brief user system data + */ +typedef struct +{ + __IO uint16_t fap; + __IO uint16_t ssb; + __IO uint16_t data0; + __IO uint16_t data1; + __IO uint16_t epp0; + __IO uint16_t epp1; + __IO uint16_t epp2; + __IO uint16_t epp3; + __IO uint16_t eopb0; + __IO uint16_t reserved1; + __IO uint16_t epp4; + __IO uint16_t epp5; + __IO uint16_t epp6; + __IO uint16_t epp7; + __IO uint16_t reserved2[12]; + __IO uint16_t qspikey[8]; +} usd_type; + +/** + * @} + */ + +#define FLASH ((flash_type *) FLASH_REG_BASE) +#define USD ((usd_type *) USD_BASE) + +/** @defgroup FLASH_exported_functions + * @{ + */ + +flag_status flash_flag_get(uint32_t flash_flag); +void flash_flag_clear(uint32_t flash_flag); +flash_status_type flash_operation_status_get(void); +flash_status_type flash_bank1_operation_status_get(void); +flash_status_type flash_bank2_operation_status_get(void); +flash_status_type flash_operation_wait_for(uint32_t time_out); +flash_status_type flash_bank1_operation_wait_for(uint32_t time_out); +flash_status_type flash_bank2_operation_wait_for(uint32_t time_out); +void flash_unlock(void); +void flash_bank1_unlock(void); +void flash_bank2_unlock(void); +void flash_lock(void); +void flash_bank1_lock(void); +void flash_bank2_lock(void); +flash_status_type flash_sector_erase(uint32_t sector_address); +flash_status_type flash_block_erase(uint32_t block_address); +flash_status_type flash_internal_all_erase(void); +flash_status_type flash_bank1_erase(void); +flash_status_type flash_bank2_erase(void); +flash_status_type flash_user_system_data_erase(void); +flash_status_type flash_eopb0_config(flash_usd_eopb0_type data); +flash_status_type flash_word_program(uint32_t address, uint32_t data); +flash_status_type flash_halfword_program(uint32_t address, uint16_t data); +flash_status_type flash_byte_program(uint32_t address, uint8_t data); +flash_status_type flash_user_system_data_program(uint32_t address, uint8_t data); +flash_status_type flash_epp_set(uint32_t *sector_bits); +void flash_epp_status_get(uint32_t *sector_bits); +flash_status_type flash_fap_enable(confirm_state new_state); +flag_status flash_fap_status_get(void); +flash_status_type flash_ssb_set(uint8_t usd_ssb); +uint8_t flash_ssb_status_get(void); +void flash_interrupt_enable(uint32_t flash_int, confirm_state new_state); +flash_status_type flash_slib_enable(uint32_t pwd, uint16_t start_sector, uint16_t inst_start_sector, uint16_t end_sector); +error_status flash_slib_disable(uint32_t pwd); +uint32_t flash_slib_remaining_count_get(void); +flag_status flash_slib_state_get(void); +uint16_t flash_slib_start_sector_get(void); +uint16_t flash_slib_inststart_sector_get(void); +uint16_t flash_slib_end_sector_get(void); +uint32_t flash_crc_calibrate(uint32_t start_sector, uint32_t sector_cnt); +void flash_nzw_boost_enable(confirm_state new_state); +void flash_continue_read_enable(confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h new file mode 100644 index 0000000000..a4d7c0be34 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h @@ -0,0 +1,565 @@ +/** + ************************************************************************** + * @file at32f435_437_gpio.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 gpio header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_GPIO_H +#define __AT32F435_437_GPIO_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/** @defgroup GPIO_pins_number_definition + * @{ + */ + +#define GPIO_PINS_0 0x0001 /*!< gpio pins number 0 */ +#define GPIO_PINS_1 0x0002 /*!< gpio pins number 1 */ +#define GPIO_PINS_2 0x0004 /*!< gpio pins number 2 */ +#define GPIO_PINS_3 0x0008 /*!< gpio pins number 3 */ +#define GPIO_PINS_4 0x0010 /*!< gpio pins number 4 */ +#define GPIO_PINS_5 0x0020 /*!< gpio pins number 5 */ +#define GPIO_PINS_6 0x0040 /*!< gpio pins number 6 */ +#define GPIO_PINS_7 0x0080 /*!< gpio pins number 7 */ +#define GPIO_PINS_8 0x0100 /*!< gpio pins number 8 */ +#define GPIO_PINS_9 0x0200 /*!< gpio pins number 9 */ +#define GPIO_PINS_10 0x0400 /*!< gpio pins number 10 */ +#define GPIO_PINS_11 0x0800 /*!< gpio pins number 11 */ +#define GPIO_PINS_12 0x1000 /*!< gpio pins number 12 */ +#define GPIO_PINS_13 0x2000 /*!< gpio pins number 13 */ +#define GPIO_PINS_14 0x4000 /*!< gpio pins number 14 */ +#define GPIO_PINS_15 0x8000 /*!< gpio pins number 15 */ +#define GPIO_PINS_ALL 0xFFFF /*!< gpio all pins */ + +/** + * @} + */ + +/** @defgroup GPIO_exported_types + * @{ + */ + +/** + * @brief gpio mode select + */ +typedef enum +{ + GPIO_MODE_INPUT = 0x00, /*!< gpio input mode */ + GPIO_MODE_OUTPUT = 0x01, /*!< gpio output mode */ + GPIO_MODE_MUX = 0x02, /*!< gpio mux function mode */ + GPIO_MODE_ANALOG = 0x03 /*!< gpio analog in/out mode */ +} gpio_mode_type; + +/** + * @brief gpio output drive strength select + */ +typedef enum +{ + GPIO_DRIVE_STRENGTH_STRONGER = 0x01, /*!< stronger sourcing/sinking strength */ + GPIO_DRIVE_STRENGTH_MODERATE = 0x02 /*!< moderate sourcing/sinking strength */ +} gpio_drive_type; + +/** + * @brief gpio output type + */ +typedef enum +{ + GPIO_OUTPUT_PUSH_PULL = 0x00, /*!< output push-pull */ + GPIO_OUTPUT_OPEN_DRAIN = 0x01 /*!< output open-drain */ +} gpio_output_type; + +/** + * @brief gpio pull type + */ +typedef enum +{ + GPIO_PULL_NONE = 0x00, /*!< floating for input, no pull for output */ + GPIO_PULL_UP = 0x01, /*!< pull-up */ + GPIO_PULL_DOWN = 0x02 /*!< pull-down */ +} gpio_pull_type; + +/** + * @brief gpio init type + */ +typedef struct +{ + uint32_t gpio_pins; /*!< pins number selection */ + gpio_output_type gpio_out_type; /*!< output type selection */ + gpio_pull_type gpio_pull; /*!< pull type selection */ + gpio_mode_type gpio_mode; /*!< mode selection */ + gpio_drive_type gpio_drive_strength; /*!< drive strength selection */ +} gpio_init_type; + +/** + * @brief gpio pins source type + */ +typedef enum +{ + GPIO_PINS_SOURCE0 = 0x00, /*!< gpio pins source number 0 */ + GPIO_PINS_SOURCE1 = 0x01, /*!< gpio pins source number 1 */ + GPIO_PINS_SOURCE2 = 0x02, /*!< gpio pins source number 2 */ + GPIO_PINS_SOURCE3 = 0x03, /*!< gpio pins source number 3 */ + GPIO_PINS_SOURCE4 = 0x04, /*!< gpio pins source number 4 */ + GPIO_PINS_SOURCE5 = 0x05, /*!< gpio pins source number 5 */ + GPIO_PINS_SOURCE6 = 0x06, /*!< gpio pins source number 6 */ + GPIO_PINS_SOURCE7 = 0x07, /*!< gpio pins source number 7 */ + GPIO_PINS_SOURCE8 = 0x08, /*!< gpio pins source number 8 */ + GPIO_PINS_SOURCE9 = 0x09, /*!< gpio pins source number 9 */ + GPIO_PINS_SOURCE10 = 0x0A, /*!< gpio pins source number 10 */ + GPIO_PINS_SOURCE11 = 0x0B, /*!< gpio pins source number 11 */ + GPIO_PINS_SOURCE12 = 0x0C, /*!< gpio pins source number 12 */ + GPIO_PINS_SOURCE13 = 0x0D, /*!< gpio pins source number 13 */ + GPIO_PINS_SOURCE14 = 0x0E, /*!< gpio pins source number 14 */ + GPIO_PINS_SOURCE15 = 0x0F /*!< gpio pins source number 15 */ +} gpio_pins_source_type; + +/** + * @brief gpio muxing function selection type + */ +typedef enum +{ + GPIO_MUX_0 = 0x00, /*!< gpio muxing function selection 0 */ + GPIO_MUX_1 = 0x01, /*!< gpio muxing function selection 1 */ + GPIO_MUX_2 = 0x02, /*!< gpio muxing function selection 2 */ + GPIO_MUX_3 = 0x03, /*!< gpio muxing function selection 3 */ + GPIO_MUX_4 = 0x04, /*!< gpio muxing function selection 4 */ + GPIO_MUX_5 = 0x05, /*!< gpio muxing function selection 5 */ + GPIO_MUX_6 = 0x06, /*!< gpio muxing function selection 6 */ + GPIO_MUX_7 = 0x07, /*!< gpio muxing function selection 7 */ + GPIO_MUX_8 = 0x08, /*!< gpio muxing function selection 8 */ + GPIO_MUX_9 = 0x09, /*!< gpio muxing function selection 9 */ + GPIO_MUX_10 = 0x0A, /*!< gpio muxing function selection 10 */ + GPIO_MUX_11 = 0x0B, /*!< gpio muxing function selection 11 */ + GPIO_MUX_12 = 0x0C, /*!< gpio muxing function selection 12 */ + GPIO_MUX_13 = 0x0D, /*!< gpio muxing function selection 13 */ + GPIO_MUX_14 = 0x0E, /*!< gpio muxing function selection 14 */ + GPIO_MUX_15 = 0x0F /*!< gpio muxing function selection 15 */ +} gpio_mux_sel_type; + +/** + * @brief type define gpio register all + */ +typedef struct +{ + /** + * @brief gpio mode register, offset:0x00 + */ + union + { + __IO uint32_t cfgr; + struct + { + __IO uint32_t iomc0 : 2; /* [1:0] */ + __IO uint32_t iomc1 : 2; /* [3:2] */ + __IO uint32_t iomc2 : 2; /* [5:4] */ + __IO uint32_t iomc3 : 2; /* [7:6] */ + __IO uint32_t iomc4 : 2; /* [9:8] */ + __IO uint32_t iomc5 : 2; /* [11:10] */ + __IO uint32_t iomc6 : 2; /* [13:12] */ + __IO uint32_t iomc7 : 2; /* [15:14] */ + __IO uint32_t iomc8 : 2; /* [17:16] */ + __IO uint32_t iomc9 : 2; /* [19:18] */ + __IO uint32_t iomc10 : 2; /* [21:20] */ + __IO uint32_t iomc11 : 2; /* [23:22] */ + __IO uint32_t iomc12 : 2; /* [25:24] */ + __IO uint32_t iomc13 : 2; /* [27:26] */ + __IO uint32_t iomc14 : 2; /* [29:28] */ + __IO uint32_t iomc15 : 2; /* [31:30] */ + } cfgr_bit; + }; + + /** + * @brief gpio output type register, offset:0x04 + */ + union + { + __IO uint32_t omode; + struct + { + __IO uint32_t om0 : 1; /* [0] */ + __IO uint32_t om1 : 1; /* [1] */ + __IO uint32_t om2 : 1; /* [2] */ + __IO uint32_t om3 : 1; /* [3] */ + __IO uint32_t om4 : 1; /* [4] */ + __IO uint32_t om5 : 1; /* [5] */ + __IO uint32_t om6 : 1; /* [6] */ + __IO uint32_t om7 : 1; /* [7] */ + __IO uint32_t om8 : 1; /* [8] */ + __IO uint32_t om9 : 1; /* [9] */ + __IO uint32_t om10 : 1; /* [10] */ + __IO uint32_t om11 : 1; /* [11] */ + __IO uint32_t om12 : 1; /* [12] */ + __IO uint32_t om13 : 1; /* [13] */ + __IO uint32_t om14 : 1; /* [14] */ + __IO uint32_t om15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } omode_bit; + }; + + /** + * @brief gpio output driver register, offset:0x08 + */ + union + { + __IO uint32_t odrvr; + struct + { + __IO uint32_t odrv0 : 2; /* [1:0] */ + __IO uint32_t odrv1 : 2; /* [3:2] */ + __IO uint32_t odrv2 : 2; /* [5:4] */ + __IO uint32_t odrv3 : 2; /* [7:6] */ + __IO uint32_t odrv4 : 2; /* [9:8] */ + __IO uint32_t odrv5 : 2; /* [11:10] */ + __IO uint32_t odrv6 : 2; /* [13:12] */ + __IO uint32_t odrv7 : 2; /* [15:14] */ + __IO uint32_t odrv8 : 2; /* [17:16] */ + __IO uint32_t odrv9 : 2; /* [19:18] */ + __IO uint32_t odrv10 : 2; /* [21:20] */ + __IO uint32_t odrv11 : 2; /* [23:22] */ + __IO uint32_t odrv12 : 2; /* [25:24] */ + __IO uint32_t odrv13 : 2; /* [27:26] */ + __IO uint32_t odrv14 : 2; /* [29:28] */ + __IO uint32_t odrv15 : 2; /* [31:30] */ + } odrvr_bit; + }; + + /** + * @brief gpio pull up/down register, offset:0x0C + */ + union + { + __IO uint32_t pull; + struct + { + __IO uint32_t pull0 : 2; /* [1:0] */ + __IO uint32_t pull1 : 2; /* [3:2] */ + __IO uint32_t pull2 : 2; /* [5:4] */ + __IO uint32_t pull3 : 2; /* [7:6] */ + __IO uint32_t pull4 : 2; /* [9:8] */ + __IO uint32_t pull5 : 2; /* [11:10] */ + __IO uint32_t pull6 : 2; /* [13:12] */ + __IO uint32_t pull7 : 2; /* [15:14] */ + __IO uint32_t pull8 : 2; /* [17:16] */ + __IO uint32_t pull9 : 2; /* [19:18] */ + __IO uint32_t pull10 : 2; /* [21:20] */ + __IO uint32_t pull11 : 2; /* [23:22] */ + __IO uint32_t pull12 : 2; /* [25:24] */ + __IO uint32_t pull13 : 2; /* [27:26] */ + __IO uint32_t pull14 : 2; /* [29:28] */ + __IO uint32_t pull15 : 2; /* [31:30] */ + } pull_bit; + }; + + /** + * @brief gpio input data register, offset:0x10 + */ + union + { + __IO uint32_t idt; + struct + { + __IO uint32_t idt0 : 1; /* [0] */ + __IO uint32_t idt1 : 1; /* [1] */ + __IO uint32_t idt2 : 1; /* [2] */ + __IO uint32_t idt3 : 1; /* [3] */ + __IO uint32_t idt4 : 1; /* [4] */ + __IO uint32_t idt5 : 1; /* [5] */ + __IO uint32_t idt6 : 1; /* [6] */ + __IO uint32_t idt7 : 1; /* [7] */ + __IO uint32_t idt8 : 1; /* [8] */ + __IO uint32_t idt9 : 1; /* [9] */ + __IO uint32_t idt10 : 1; /* [10] */ + __IO uint32_t idt11 : 1; /* [11] */ + __IO uint32_t idt12 : 1; /* [12] */ + __IO uint32_t idt13 : 1; /* [13] */ + __IO uint32_t idt14 : 1; /* [14] */ + __IO uint32_t idt15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } idt_bit; + }; + + /** + * @brief gpio output data register, offset:0x14 + */ + union + { + __IO uint32_t odt; + struct + { + __IO uint32_t odt0 : 1; /* [0] */ + __IO uint32_t odt1 : 1; /* [1] */ + __IO uint32_t odt2 : 1; /* [2] */ + __IO uint32_t odt3 : 1; /* [3] */ + __IO uint32_t odt4 : 1; /* [4] */ + __IO uint32_t odt5 : 1; /* [5] */ + __IO uint32_t odt6 : 1; /* [6] */ + __IO uint32_t odt7 : 1; /* [7] */ + __IO uint32_t odt8 : 1; /* [8] */ + __IO uint32_t odt9 : 1; /* [9] */ + __IO uint32_t odt10 : 1; /* [10] */ + __IO uint32_t odt11 : 1; /* [11] */ + __IO uint32_t odt12 : 1; /* [12] */ + __IO uint32_t odt13 : 1; /* [13] */ + __IO uint32_t odt14 : 1; /* [14] */ + __IO uint32_t odt15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } odt_bit; + }; + + /** + * @brief gpio scr register, offset:0x18 + */ + union + { + __IO uint32_t scr; + struct + { + __IO uint32_t iosb0 : 1; /* [0] */ + __IO uint32_t iosb1 : 1; /* [1] */ + __IO uint32_t iosb2 : 1; /* [2] */ + __IO uint32_t iosb3 : 1; /* [3] */ + __IO uint32_t iosb4 : 1; /* [4] */ + __IO uint32_t iosb5 : 1; /* [5] */ + __IO uint32_t iosb6 : 1; /* [6] */ + __IO uint32_t iosb7 : 1; /* [7] */ + __IO uint32_t iosb8 : 1; /* [8] */ + __IO uint32_t iosb9 : 1; /* [9] */ + __IO uint32_t iosb10 : 1; /* [10] */ + __IO uint32_t iosb11 : 1; /* [11] */ + __IO uint32_t iosb12 : 1; /* [12] */ + __IO uint32_t iosb13 : 1; /* [13] */ + __IO uint32_t iosb14 : 1; /* [14] */ + __IO uint32_t iosb15 : 1; /* [15] */ + __IO uint32_t iocb0 : 1; /* [16] */ + __IO uint32_t iocb1 : 1; /* [17] */ + __IO uint32_t iocb2 : 1; /* [18] */ + __IO uint32_t iocb3 : 1; /* [19] */ + __IO uint32_t iocb4 : 1; /* [20] */ + __IO uint32_t iocb5 : 1; /* [21] */ + __IO uint32_t iocb6 : 1; /* [22] */ + __IO uint32_t iocb7 : 1; /* [23] */ + __IO uint32_t iocb8 : 1; /* [24] */ + __IO uint32_t iocb9 : 1; /* [25] */ + __IO uint32_t iocb10 : 1; /* [26] */ + __IO uint32_t iocb11 : 1; /* [27] */ + __IO uint32_t iocb12 : 1; /* [28] */ + __IO uint32_t iocb13 : 1; /* [29] */ + __IO uint32_t iocb14 : 1; /* [30] */ + __IO uint32_t iocb15 : 1; /* [31] */ + } scr_bit; + }; + + /** + * @brief gpio wpen register, offset:0x1C + */ + union + { + __IO uint32_t wpr; + struct + { + __IO uint32_t wpen0 : 1; /* [0] */ + __IO uint32_t wpen1 : 1; /* [1] */ + __IO uint32_t wpen2 : 1; /* [2] */ + __IO uint32_t wpen3 : 1; /* [3] */ + __IO uint32_t wpen4 : 1; /* [4] */ + __IO uint32_t wpen5 : 1; /* [5] */ + __IO uint32_t wpen6 : 1; /* [6] */ + __IO uint32_t wpen7 : 1; /* [7] */ + __IO uint32_t wpen8 : 1; /* [8] */ + __IO uint32_t wpen9 : 1; /* [9] */ + __IO uint32_t wpen10 : 1; /* [10] */ + __IO uint32_t wpen11 : 1; /* [11] */ + __IO uint32_t wpen12 : 1; /* [12] */ + __IO uint32_t wpen13 : 1; /* [13] */ + __IO uint32_t wpen14 : 1; /* [14] */ + __IO uint32_t wpen15 : 1; /* [15] */ + __IO uint32_t wpseq : 1; /* [16] */ + __IO uint32_t reserved1 : 15;/* [31:17] */ + } wpr_bit; + }; + + /** + * @brief gpio muxl register, offset:0x20 + */ + union + { + __IO uint32_t muxl; + struct + { + __IO uint32_t muxl0 : 4; /* [3:0] */ + __IO uint32_t muxl1 : 4; /* [7:4] */ + __IO uint32_t muxl2 : 4; /* [11:8] */ + __IO uint32_t muxl3 : 4; /* [15:12] */ + __IO uint32_t muxl4 : 4; /* [19:16] */ + __IO uint32_t muxl5 : 4; /* [23:20] */ + __IO uint32_t muxl6 : 4; /* [27:24] */ + __IO uint32_t muxl7 : 4; /* [31:28] */ + } muxl_bit; + }; + + /** + * @brief gpio muxh register, offset:0x24 + */ + union + { + __IO uint32_t muxh; + struct + { + __IO uint32_t muxh8 : 4; /* [3:0] */ + __IO uint32_t muxh9 : 4; /* [7:4] */ + __IO uint32_t muxh10 : 4; /* [11:8] */ + __IO uint32_t muxh11 : 4; /* [15:12] */ + __IO uint32_t muxh12 : 4; /* [19:16] */ + __IO uint32_t muxh13 : 4; /* [23:20] */ + __IO uint32_t muxh14 : 4; /* [27:24] */ + __IO uint32_t muxh15 : 4; /* [31:28] */ + } muxh_bit; + }; + + /** + * @brief gpio clr register, offset:0x28 + */ + union + { + __IO uint32_t clr; + struct + { + __IO uint32_t iocb0 : 1; /* [0] */ + __IO uint32_t iocb1 : 1; /* [1] */ + __IO uint32_t iocb2 : 1; /* [2] */ + __IO uint32_t iocb3 : 1; /* [3] */ + __IO uint32_t iocb4 : 1; /* [4] */ + __IO uint32_t iocb5 : 1; /* [5] */ + __IO uint32_t iocb6 : 1; /* [6] */ + __IO uint32_t iocb7 : 1; /* [7] */ + __IO uint32_t iocb8 : 1; /* [8] */ + __IO uint32_t iocb9 : 1; /* [9] */ + __IO uint32_t iocb10 : 1; /* [10] */ + __IO uint32_t iocb11 : 1; /* [11] */ + __IO uint32_t iocb12 : 1; /* [12] */ + __IO uint32_t iocb13 : 1; /* [13] */ + __IO uint32_t iocb14 : 1; /* [14] */ + __IO uint32_t iocb15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } clr_bit; + }; + + /** + * @brief gpio reserved1 register, offset:0x2C~0x38 + */ + __IO uint32_t reserved1[4]; + + /** + * @brief gpio hdrv register, offset:0x3C + */ + union + { + __IO uint32_t hdrv; + struct + { + __IO uint32_t hdrv0 : 1; /* [0] */ + __IO uint32_t hdrv1 : 1; /* [1] */ + __IO uint32_t hdrv2 : 1; /* [2] */ + __IO uint32_t hdrv3 : 1; /* [3] */ + __IO uint32_t hdrv4 : 1; /* [4] */ + __IO uint32_t hdrv5 : 1; /* [5] */ + __IO uint32_t hdrv6 : 1; /* [6] */ + __IO uint32_t hdrv7 : 1; /* [7] */ + __IO uint32_t hdrv8 : 1; /* [8] */ + __IO uint32_t hdrv9 : 1; /* [9] */ + __IO uint32_t hdrv10 : 1; /* [10] */ + __IO uint32_t hdrv11 : 1; /* [11] */ + __IO uint32_t hdrv12 : 1; /* [12] */ + __IO uint32_t hdrv13 : 1; /* [13] */ + __IO uint32_t hdrv14 : 1; /* [14] */ + __IO uint32_t hdrv15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } hdrv_bit; + }; + +} gpio_type; + +/** + * @} + */ + +#define GPIOA ((gpio_type *) GPIOA_BASE) +#define GPIOB ((gpio_type *) GPIOB_BASE) +#define GPIOC ((gpio_type *) GPIOC_BASE) +#define GPIOD ((gpio_type *) GPIOD_BASE) +#define GPIOE ((gpio_type *) GPIOE_BASE) +#define GPIOF ((gpio_type *) GPIOF_BASE) +#define GPIOG ((gpio_type *) GPIOG_BASE) +#define GPIOH ((gpio_type *) GPIOH_BASE) + +/** @defgroup GPIO_exported_functions + * @{ + */ + +void gpio_reset(gpio_type *gpio_x); +void gpio_init(gpio_type *gpio_x, gpio_init_type *gpio_init_struct); +void gpio_default_para_init(gpio_init_type *gpio_init_struct); +flag_status gpio_input_data_bit_read(gpio_type *gpio_x, uint16_t pins); +uint16_t gpio_input_data_read(gpio_type *gpio_x); +flag_status gpio_output_data_bit_read(gpio_type *gpio_x, uint16_t pins); +uint16_t gpio_output_data_read(gpio_type *gpio_x); +void gpio_bits_set(gpio_type *gpio_x, uint16_t pins); +void gpio_bits_reset(gpio_type *gpio_x, uint16_t pins); +void gpio_bits_write(gpio_type *gpio_x, uint16_t pins, confirm_state bit_state); +void gpio_port_write(gpio_type *gpio_x, uint16_t port_value); +void gpio_pin_wp_config(gpio_type *gpio_x, uint16_t pins); +void gpio_pins_huge_driven_config(gpio_type *gpio_x, uint16_t pins, confirm_state new_state); +void gpio_pin_mux_config(gpio_type *gpio_x, gpio_pins_source_type gpio_pin_source, gpio_mux_sel_type gpio_mux); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h new file mode 100644 index 0000000000..89b308e9d4 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h @@ -0,0 +1,479 @@ +/** + ************************************************************************** + * @file at32f435_437_i2c.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 i2c header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_I2C_H +#define __AT32F435_437_I2C_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/** + * @brief maximum number of single transfers + */ +#define MAX_TRANSFER_CNT 255 /*!< maximum number of single transfers */ + +/** @defgroup I2C_interrupts_definition + * @brief i2c interrupt + * @{ + */ + +#define I2C_TD_INT ((uint32_t)0x00000002) /*!< i2c transmit data interrupt */ +#define I2C_RD_INT ((uint32_t)0x00000004) /*!< i2c receive data interrupt */ +#define I2C_ADDR_INT ((uint32_t)0x00000008) /*!< i2c address match interrupt */ +#define I2C_ACKFIAL_INT ((uint32_t)0x00000010) /*!< i2c ack fail interrupt */ +#define I2C_STOP_INT ((uint32_t)0x00000020) /*!< i2c stop detect interrupt */ +#define I2C_TDC_INT ((uint32_t)0x00000040) /*!< i2c transmit data complete interrupt */ +#define I2C_ERR_INT ((uint32_t)0x00000080) /*!< i2c bus error interrupt */ + +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @brief i2c flag + * @{ + */ + +#define I2C_TDBE_FLAG ((uint32_t)0x00000001) /*!< i2c transmit data buffer empty flag */ +#define I2C_TDIS_FLAG ((uint32_t)0x00000002) /*!< i2c send interrupt status */ +#define I2C_RDBF_FLAG ((uint32_t)0x00000004) /*!< i2c receive data buffer full flag */ +#define I2C_ADDRF_FLAG ((uint32_t)0x00000008) /*!< i2c 0~7 bit address match flag */ +#define I2C_ACKFAIL_FLAG ((uint32_t)0x00000010) /*!< i2c acknowledge failure flag */ +#define I2C_STOPF_FLAG ((uint32_t)0x00000020) /*!< i2c stop condition generation complete flag */ +#define I2C_TDC_FLAG ((uint32_t)0x00000040) /*!< i2c transmit data complete flag */ +#define I2C_TCRLD_FLAG ((uint32_t)0x00000080) /*!< i2c transmission is complete, waiting to load data */ +#define I2C_BUSERR_FLAG ((uint32_t)0x00000100) /*!< i2c bus error flag */ +#define I2C_ARLOST_FLAG ((uint32_t)0x00000200) /*!< i2c arbitration lost flag */ +#define I2C_OUF_FLAG ((uint32_t)0x00000400) /*!< i2c overflow or underflow flag */ +#define I2C_PECERR_FLAG ((uint32_t)0x00000800) /*!< i2c pec receive error flag */ +#define I2C_TMOUT_FLAG ((uint32_t)0x00001000) /*!< i2c smbus timeout flag */ +#define I2C_ALERTF_FLAG ((uint32_t)0x00002000) /*!< i2c smbus alert flag */ +#define I2C_BUSYF_FLAG ((uint32_t)0x00008000) /*!< i2c bus busy flag transmission mode */ +#define I2C_SDIR_FLAG ((uint32_t)0x00010000) /*!< i2c slave data transmit direction */ + +/** + * @} + */ + +/** @defgroup I2C_exported_types + * @{ + */ + +/** + * @brief i2c smbus mode set + */ +typedef enum +{ + I2C_SMBUS_MODE_DEVICE = 0x00, /*!< smbus device mode */ + I2C_SMBUS_MODE_HOST = 0x01 /*!< smbus host mode */ +} i2c_smbus_mode_type; + +/** + * @brief i2c address mode + */ +typedef enum +{ + I2C_ADDRESS_MODE_7BIT = 0x00, /*!< 7bit address mode */ + I2C_ADDRESS_MODE_10BIT = 0x01 /*!< 10bit address mode */ +} i2c_address_mode_type; + +/** + * @brief i2c transfer direction + */ +typedef enum +{ + I2C_DIR_TRANSMIT = 0x00, /*!< master request a write transfer */ + I2C_DIR_RECEIVE = 0x01 /*!< master request a read transfer */ +} i2c_transfer_dir_type; + +/** + * @brief i2c dma requests direction + */ +typedef enum +{ + I2C_DMA_REQUEST_TX = 0x00, /*!< dma transmit request */ + I2C_DMA_REQUEST_RX = 0x01 /*!< dma receive request */ +} i2c_dma_request_type; + +/** + * @brief i2c smbus alert pin set + */ +typedef enum +{ + I2C_SMBUS_ALERT_HIGH = 0x00, /*!< smbus alert pin set high */ + I2C_SMBUS_ALERT_LOW = 0x01 /*!< smbus alert pin set low */ +} i2c_smbus_alert_set_type; + +/** + * @brief i2c clock timeout detection mode + */ +typedef enum +{ + I2C_TIMEOUT_DETCET_LOW = 0x00, /*!< detect low level timeout */ + I2C_TIMEOUT_DETCET_HIGH = 0x01 /*!< detect high level timeout */ +} i2c_timeout_detcet_type; + +/** + * @brief i2c own address2 mask + */ +typedef enum +{ + I2C_ADDR2_NOMASK = 0x00, /*!< compare bit [7:1] */ + I2C_ADDR2_MASK01 = 0x01, /*!< only compare bit [7:2] */ + I2C_ADDR2_MASK02 = 0x02, /*!< only compare bit [7:2] */ + I2C_ADDR2_MASK03 = 0x03, /*!< only compare bit [7:3] */ + I2C_ADDR2_MASK04 = 0x04, /*!< only compare bit [7:4] */ + I2C_ADDR2_MASK05 = 0x05, /*!< only compare bit [7:5] */ + I2C_ADDR2_MASK06 = 0x06, /*!< only compare bit [7:6] */ + I2C_ADDR2_MASK07 = 0x07 /*!< only compare bit [7] */ +} i2c_addr2_mask_type; + +/** + * @brief i2c reload end mode + */ +typedef enum +{ + I2C_AUTO_STOP_MODE = 0x02000000, /*!< auto generate stop mode */ + I2C_SOFT_STOP_MODE = 0x00000000, /*!< soft generate stop mode */ + I2C_RELOAD_MODE = 0x01000000 /*!< reload mode */ +} i2c_reload_stop_mode_type; + +/** + * @brief i2c start mode + */ +typedef enum +{ + I2C_WITHOUT_START = 0x00000000, /*!< transfer data without start condition */ + I2C_GEN_START_READ = 0x00002400, /*!< read data and generate start */ + I2C_GEN_START_WRITE = 0x00002000 /*!< send data and generate start */ +} i2c_start_mode_type; + +/** + * @brief type define i2c register all + */ +typedef struct +{ + /** + * @brief i2c ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t i2cen : 1; /* [0] */ + __IO uint32_t tdien : 1; /* [1] */ + __IO uint32_t rdien : 1; /* [2] */ + __IO uint32_t addrien : 1; /* [3] */ + __IO uint32_t ackfailien : 1; /* [4] */ + __IO uint32_t stopien : 1; /* [5] */ + __IO uint32_t tdcien : 1; /* [6] */ + __IO uint32_t errien : 1; /* [7] */ + __IO uint32_t dflt : 4; /* [11:8] */ + __IO uint32_t reserved1 : 2; /* [13:12] */ + __IO uint32_t dmaten : 1; /* [14] */ + __IO uint32_t dmaren : 1; /* [15] */ + __IO uint32_t sctrl : 1; /* [16] */ + __IO uint32_t stretch : 1; /* [17] */ + __IO uint32_t reserved2 : 1; /* [18] */ + __IO uint32_t gcaen : 1; /* [19] */ + __IO uint32_t haddren : 1; /* [20] */ + __IO uint32_t devaddren : 1; /* [21] */ + __IO uint32_t smbalert : 1; /* [22] */ + __IO uint32_t pecen : 1; /* [23] */ + __IO uint32_t reserved3 : 8; /* [31:24] */ + } ctrl1_bit; + }; + + /** + * @brief i2c ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t saddr : 10;/* [9:0] */ + __IO uint32_t dir : 1; /* [10] */ + __IO uint32_t addr10 : 1; /* [11] */ + __IO uint32_t readh10 : 1; /* [12] */ + __IO uint32_t genstart : 1; /* [13] */ + __IO uint32_t genstop : 1; /* [14] */ + __IO uint32_t nacken : 1; /* [15] */ + __IO uint32_t cnt : 8; /* [23:16] */ + __IO uint32_t rlden : 1; /* [24] */ + __IO uint32_t astopen : 1; /* [25] */ + __IO uint32_t pecten : 1; /* [26] */ + __IO uint32_t reserved1 : 5; /* [31:27] */ + } ctrl2_bit; + }; + + /** + * @brief i2c oaddr1 register, offset:0x08 + */ + union + { + __IO uint32_t oaddr1; + struct + { + __IO uint32_t addr1 : 10;/* [9:0] */ + __IO uint32_t addr1mode : 1; /* [10] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t addr1en : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } oaddr1_bit; + }; + + /** + * @brief i2c oaddr2 register, offset:0x0c + */ + union + { + __IO uint32_t oaddr2; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t addr2 : 7; /* [7:1] */ + __IO uint32_t addr2mask : 3; /* [10:8] */ + __IO uint32_t reserved2 : 4; /* [14:11] */ + __IO uint32_t addr2en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } oaddr2_bit; + }; + + /** + * @brief i2c clkctrl register, offset:0x10 + */ + union + { + __IO uint32_t clkctrl; + struct + { + __IO uint32_t scll : 8; /* [7:0] */ + __IO uint32_t sclh : 8; /* [15:8] */ + __IO uint32_t sdad : 4; /* [19:16] */ + __IO uint32_t scld : 4; /* [23:20] */ + __IO uint32_t divh : 4; /* [27:24] */ + __IO uint32_t divl : 4; /* [31:28] */ + } clkctrl_bit; + }; + + /** + * @brief i2c timeout register, offset:0x14 + */ + union + { + __IO uint32_t timeout; + struct + { + __IO uint32_t totime : 12;/* [11:0] */ + __IO uint32_t tomode : 1; /* [12] */ + __IO uint32_t reserved1 : 2; /* [14:13] */ + __IO uint32_t toen : 1; /* [15] */ + __IO uint32_t exttime : 12;/* [27:16] */ + __IO uint32_t reserved2 : 3; /* [30:28] */ + __IO uint32_t exten : 1; /* [31] */ + } timeout_bit; + }; + + /** + * @brief i2c sts register, offset:0x18 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t tdbe : 1; /* [0] */ + __IO uint32_t tdis : 1; /* [1] */ + __IO uint32_t rdbf : 1; /* [2] */ + __IO uint32_t addrf : 1; /* [3] */ + __IO uint32_t ackfail : 1; /* [4] */ + __IO uint32_t stopf : 1; /* [5] */ + __IO uint32_t tdc : 1; /* [6] */ + __IO uint32_t tcrld : 1; /* [7] */ + __IO uint32_t buserr : 1; /* [8] */ + __IO uint32_t arlost : 1; /* [9] */ + __IO uint32_t ouf : 1; /* [10] */ + __IO uint32_t pecerr : 1; /* [11] */ + __IO uint32_t tmout : 1; /* [12] */ + __IO uint32_t alertf : 1; /* [13] */ + __IO uint32_t reserved1 : 1; /* [14] */ + __IO uint32_t busyf : 1; /* [15] */ + __IO uint32_t sdir : 1; /* [16] */ + __IO uint32_t addr : 7; /* [23:17] */ + __IO uint32_t reserved2 : 8; /* [31:24] */ + } sts_bit; + }; + + /** + * @brief i2c clr register, offset:0x1c + */ + union + { + __IO uint32_t clr; + struct + { + __IO uint32_t reserved1 : 3; /* [2:0] */ + __IO uint32_t addrc : 1; /* [3] */ + __IO uint32_t ackfailc : 1; /* [4] */ + __IO uint32_t stopc : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [6:7] */ + __IO uint32_t buserrc : 1; /* [8] */ + __IO uint32_t arlostc : 1; /* [9] */ + __IO uint32_t oufc : 1; /* [10] */ + __IO uint32_t pecerrc : 1; /* [11] */ + __IO uint32_t tmoutc : 1; /* [12] */ + __IO uint32_t alertc : 1; /* [13] */ + __IO uint32_t reserved3 : 18;/* [31:14] */ + } clr_bit; + }; + + /** + * @brief i2c pec register, offset:0x20 + */ + union + { + __IO uint32_t pec; + struct + { + __IO uint32_t pecval : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } pec_bit; + }; + + /** + * @brief i2c rxdt register, offset:0x20 + */ + union + { + __IO uint32_t rxdt; + struct + { + __IO uint32_t dt : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } rxdt_bit; + }; + + /** + * @brief i2c txdt register, offset:0x20 + */ + union + { + __IO uint32_t txdt; + struct + { + __IO uint32_t dt : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } txdt_bit; + }; + +} i2c_type; + +/** + * @} + */ + +#define I2C1 ((i2c_type *) I2C1_BASE) +#define I2C2 ((i2c_type *) I2C2_BASE) +#define I2C3 ((i2c_type *) I2C3_BASE) + +/** @defgroup I2C_exported_functions + * @{ + */ + +void i2c_reset(i2c_type *i2c_x); +void i2c_init(i2c_type *i2c_x, uint8_t dfilters, uint32_t clk); +void i2c_own_address1_set(i2c_type *i2c_x, i2c_address_mode_type mode, uint16_t address); +void i2c_own_address2_set(i2c_type *i2c_x, uint8_t address, i2c_addr2_mask_type mask); +void i2c_own_address2_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_smbus_enable(i2c_type *i2c_x, i2c_smbus_mode_type mode, confirm_state new_state); +void i2c_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_clock_stretch_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_ack_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_addr10_mode_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_transfer_addr_set(i2c_type *i2c_x, uint16_t address); +uint16_t i2c_transfer_addr_get(i2c_type *i2c_x); +void i2c_transfer_dir_set(i2c_type *i2c_x, i2c_transfer_dir_type i2c_direction); +i2c_transfer_dir_type i2c_transfer_dir_get(i2c_type *i2c_x); +uint8_t i2c_matched_addr_get(i2c_type *i2c_x); +void i2c_auto_stop_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_reload_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_cnt_set(i2c_type *i2c_x, uint8_t cnt); +void i2c_addr10_header_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_general_call_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_smbus_alert_set(i2c_type *i2c_x, i2c_smbus_alert_set_type level); +void i2c_slave_data_ctrl_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_pec_calculate_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_pec_transmit_enable(i2c_type *i2c_x, confirm_state new_state); +uint8_t i2c_pec_value_get(i2c_type *i2c_x); +void i2c_timeout_set(i2c_type *i2c_x, uint16_t timeout); +void i2c_timeout_detcet_set(i2c_type *i2c_x, i2c_timeout_detcet_type mode); +void i2c_timeout_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_ext_timeout_set(i2c_type *i2c_x, uint16_t timeout); +void i2c_ext_timeout_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_interrupt_enable(i2c_type *i2c_x, uint32_t source, confirm_state new_state); +flag_status i2c_interrupt_get(i2c_type *i2c_x, uint16_t source); +void i2c_dma_enable(i2c_type *i2c_x, i2c_dma_request_type dma_req, confirm_state new_state); +void i2c_transmit_set(i2c_type *i2c_x, uint16_t address, uint8_t cnt, i2c_reload_stop_mode_type rld_stop, i2c_start_mode_type start); +void i2c_start_generate(i2c_type *i2c_x); +void i2c_stop_generate(i2c_type *i2c_x); +void i2c_data_send(i2c_type *i2c_x, uint8_t data); +uint8_t i2c_data_receive(i2c_type *i2c_x); +flag_status i2c_flag_get(i2c_type *i2c_x, uint32_t flag); +void i2c_flag_clear(i2c_type *i2c_x, uint32_t flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h new file mode 100644 index 0000000000..d965d02cc2 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h @@ -0,0 +1,125 @@ +/** + ************************************************************************** + * @file at32f435_437_misc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 misc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_MISC_H +#define __AT32F435_437_MISC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/** @defgroup MISC_vector_table_base_address + * @{ + */ + +#define NVIC_VECTTAB_RAM ((uint32_t)0x20000000) /*!< nvic vector table based ram address */ +#define NVIC_VECTTAB_FLASH ((uint32_t)0x08000000) /*!< nvic vector table based flash address */ + +/** + * @} + */ + +/** @defgroup MISC_exported_types + * @{ + */ + +/** + * @brief nvic interrupt priority group + */ +typedef enum +{ + NVIC_PRIORITY_GROUP_0 = ((uint32_t)0x7), /*!< 0 bits for preemption priority, 4 bits for subpriority */ + NVIC_PRIORITY_GROUP_1 = ((uint32_t)0x6), /*!< 1 bits for preemption priority, 3 bits for subpriority */ + NVIC_PRIORITY_GROUP_2 = ((uint32_t)0x5), /*!< 2 bits for preemption priority, 2 bits for subpriority */ + NVIC_PRIORITY_GROUP_3 = ((uint32_t)0x4), /*!< 3 bits for preemption priority, 1 bits for subpriority */ + NVIC_PRIORITY_GROUP_4 = ((uint32_t)0x3) /*!< 4 bits for preemption priority, 0 bits for subpriority */ +} nvic_priority_group_type; + +/** + * @brief nvic low power mode + */ +typedef enum +{ + NVIC_LP_SLEEPONEXIT = 0x02, /*!< enable sleep-on-exit feature */ + NVIC_LP_SLEEPDEEP = 0x04, /*!< enable sleep-deep output signal when entering sleep mode */ + NVIC_LP_SEVONPEND = 0x10 /*!< send event on pending */ +} nvic_lowpower_mode_type; + +/** + * @brief systick clock source + */ +typedef enum +{ + SYSTICK_CLOCK_SOURCE_AHBCLK_DIV8 = ((uint32_t)0x00000000), /*!< systick clock source from core clock div8 */ + SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV = ((uint32_t)0x00000004) /*!< systick clock source from core clock */ +} systick_clock_source_type; + +/** + * @} + */ + +/** @defgroup MISC_exported_functions + * @{ + */ + +void nvic_system_reset(void); +void nvic_irq_enable(IRQn_Type irqn, uint32_t preempt_priority, uint32_t sub_priority); +void nvic_irq_disable(IRQn_Type irqn); +void nvic_priority_group_config(nvic_priority_group_type priority_group); +void nvic_vector_table_set(uint32_t base, uint32_t offset); +void nvic_lowpower_mode_config(nvic_lowpower_mode_type lp_mode, confirm_state new_state); +void systick_clock_source_config(systick_clock_source_type source); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h new file mode 100644 index 0000000000..16304be763 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h @@ -0,0 +1,232 @@ +/** + ************************************************************************** + * @file at32f435_437_pwc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 pwr header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_PWC_H +#define __AT32F435_437_PWC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup PWC + * @{ + */ + +/** @defgroup PWC_flags_definition + * @brief pwc flag + * @{ + */ + +#define PWC_WAKEUP_FLAG ((uint32_t)0x00000001) /*!< wakeup flag */ +#define PWC_STANDBY_FLAG ((uint32_t)0x00000002) /*!< standby flag */ +#define PWC_PVM_OUTPUT_FLAG ((uint32_t)0x00000004) /*!< pvm output flag */ + +/** + * @} + */ + +/** + * @brief pwc wakeup pin num definition + */ +#define PWC_WAKEUP_PIN_1 ((uint32_t)0x00000100) /*!< standby wake-up pin1 */ +#define PWC_WAKEUP_PIN_2 ((uint32_t)0x00000200) /*!< standby wake-up pin2 */ + +/** + * @brief select ldo output voltage. + * @param val: set the ldo output voltage. + * this parameter can be one of the following values: + * - PWC_LDO_OUTPUT_1V3: system clock up to 288MHz. + * - PWC_LDO_OUTPUT_1V2: system clock up to 240MHz. + * - PWC_LDO_OUTPUT_1V1: system clock up to 192MHz. + * - PWC_LDO_OUTPUT_1V0: system clock up to 144MHz. + * @note useage limited. + * PWC_LDO_OUTPUT_1V3: operation temperature range -40~85 degree, VDD must over 3.0V. + */ +#define pwc_ldo_output_voltage_set(val) (PWC->ldoov_bit.ldoovsel = val) + +/** @defgroup PWC_exported_types + * @{ + */ + +/** + * @brief pwc pvm voltage type + */ +typedef enum +{ + PWC_PVM_VOLTAGE_2V3 = 0x01, /*!< power voltage monitoring boundary 2.3v */ + PWC_PVM_VOLTAGE_2V4 = 0x02, /*!< power voltage monitoring boundary 2.4v */ + PWC_PVM_VOLTAGE_2V5 = 0x03, /*!< power voltage monitoring boundary 2.5v */ + PWC_PVM_VOLTAGE_2V6 = 0x04, /*!< power voltage monitoring boundary 2.6v */ + PWC_PVM_VOLTAGE_2V7 = 0x05, /*!< power voltage monitoring boundary 2.7v */ + PWC_PVM_VOLTAGE_2V8 = 0x06, /*!< power voltage monitoring boundary 2.8v */ + PWC_PVM_VOLTAGE_2V9 = 0x07 /*!< power voltage monitoring boundary 2.9v */ +} pwc_pvm_voltage_type; + +/** + * @brief pwc ldo output voltage type + */ +typedef enum +{ + PWC_LDO_OUTPUT_1V3 = 0x01, /*!< ldo output voltage is 1.3v */ + PWC_LDO_OUTPUT_1V2 = 0x00, /*!< ldo output voltage is 1.2v */ + PWC_LDO_OUTPUT_1V1 = 0x04, /*!< ldo output voltage is 1.1v */ + PWC_LDO_OUTPUT_1V0 = 0x05, /*!< ldo output voltage is 1.0v */ +} pwc_ldo_output_voltage_type; + +/** + * @brief pwc sleep enter type + */ +typedef enum +{ + PWC_SLEEP_ENTER_WFI = 0x00, /*!< use wfi enter sleep mode */ + PWC_SLEEP_ENTER_WFE = 0x01 /*!< use wfe enter sleep mode */ +} pwc_sleep_enter_type ; + +/** + * @brief pwc deep sleep enter type + */ +typedef enum +{ + PWC_DEEP_SLEEP_ENTER_WFI = 0x00, /*!< use wfi enter deepsleep mode */ + PWC_DEEP_SLEEP_ENTER_WFE = 0x01 /*!< use wfe enter deepsleep mode */ +} pwc_deep_sleep_enter_type ; + +/** + * @brief pwc regulator type + */ +typedef enum +{ + PWC_REGULATOR_ON = 0x00, /*!< voltage regulator state on when deepsleep mode */ + PWC_REGULATOR_LOW_POWER = 0x01 /*!< voltage regulator state low power when deepsleep mode */ +} pwc_regulator_type ; + +/** + * @brief type define pwc register all + */ +typedef struct +{ + /** + * @brief pwc ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t vrsel : 1; /* [0] */ + __IO uint32_t lpsel : 1; /* [1] */ + __IO uint32_t clswef : 1; /* [2] */ + __IO uint32_t clsef : 1; /* [3] */ + __IO uint32_t pvmen : 1; /* [4] */ + __IO uint32_t pvmsel : 3; /* [7:5] */ + __IO uint32_t bpwen : 1; /* [8] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } ctrl_bit; + }; + + /** + * @brief pwc ctrlsts register, offset:0x04 + */ + union + { + __IO uint32_t ctrlsts; + struct + { + __IO uint32_t swef : 1; /* [0] */ + __IO uint32_t sef : 1; /* [1] */ + __IO uint32_t pvmof : 1; /* [2] */ + __IO uint32_t reserved1 : 5; /* [7:3] */ + __IO uint32_t swpen1 : 1; /* [8] */ + __IO uint32_t swpen2 : 1; /* [9] */ + __IO uint32_t reserved2 : 22;/* [31:10] */ + } ctrlsts_bit; + }; + + __IO uint32_t reserved1[2]; + + /** + * @brief pwc ldoov register, offset:0x10 + */ + union + { + __IO uint32_t ldoov; + struct + { + __IO uint32_t ldoovsel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 29;/* [31:3] */ + } ldoov_bit; + }; + +} pwc_type; + +/** + * @} + */ + +#define PWC ((pwc_type *) PWC_BASE) + +/** @defgroup PWC_exported_functions + * @{ + */ + +void pwc_reset(void); +void pwc_battery_powered_domain_access(confirm_state new_state); +void pwc_pvm_level_select(pwc_pvm_voltage_type pvm_voltage); +void pwc_power_voltage_monitor_enable(confirm_state new_state); +void pwc_wakeup_pin_enable(uint32_t pin_num, confirm_state new_state); +void pwc_flag_clear(uint32_t pwc_flag); +flag_status pwc_flag_get(uint32_t pwc_flag); +void pwc_sleep_mode_enter(pwc_sleep_enter_type pwc_sleep_enter); +void pwc_deep_sleep_mode_enter(pwc_deep_sleep_enter_type pwc_deep_sleep_enter); +void pwc_voltage_regulate_set(pwc_regulator_type pwc_regulator); +void pwc_standby_mode_enter(void); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h new file mode 100644 index 0000000000..6e3315eeae --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h @@ -0,0 +1,555 @@ +/** + ************************************************************************** + * @file at32f435_437_qspi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 qspi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_QSPI_H +#define __AT32F435_437_QSPI_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup QSPI + * @{ + */ + +/** @defgroup QSPI_flags_definition + * @brief qspi flag + * @{ + */ + +#define QSPI_CMDSTS_FLAG ((uint32_t)0x00000001) /*!< qspi command complete status flag */ +#define QSPI_RXFIFORDY_FLAG ((uint32_t)0x00000002) /*!< qspi rxfifo ready status flag */ +#define QSPI_TXFIFORDY_FLAG ((uint32_t)0x00000004) /*!< qspi txfifo ready status flag */ + +/** + * @} + */ + +/** @defgroup QSPI_exported_types + * @{ + */ + +/** + * @brief qspi xip read access mode type + */ +typedef enum +{ + QSPI_XIPR_SEL_MODED = 0x00, /*!< qspi xip read select mode d */ + QSPI_XIPR_SEL_MODET = 0x01 /*!< qspi xip read select mode t */ +} qspi_xip_read_sel_type; + +/** + * @brief qspi xip write access mode type + */ +typedef enum +{ + QSPI_XIPW_SEL_MODED = 0x00, /*!< qspi xip write select mode d */ + QSPI_XIPW_SEL_MODET = 0x01 /*!< qspi xip write select mode t */ +} qspi_xip_write_sel_type; + +/** + * @brief qspi busy bit offset position in status register type + */ +typedef enum +{ + QSPI_BUSY_OFFSET_0 = 0x00, /*!< qspi busy bit offset position 0 */ + QSPI_BUSY_OFFSET_1 = 0x01, /*!< qspi busy bit offset position 1 */ + QSPI_BUSY_OFFSET_2 = 0x02, /*!< qspi busy bit offset position 2 */ + QSPI_BUSY_OFFSET_3 = 0x03, /*!< qspi busy bit offset position 3 */ + QSPI_BUSY_OFFSET_4 = 0x04, /*!< qspi busy bit offset position 4 */ + QSPI_BUSY_OFFSET_5 = 0x05, /*!< qspi busy bit offset position 5 */ + QSPI_BUSY_OFFSET_6 = 0x06, /*!< qspi busy bit offset position 6 */ + QSPI_BUSY_OFFSET_7 = 0x07 /*!< qspi busy bit offset position 7 */ +} qspi_busy_pos_type; + +/** + * @brief qspi read status configure type + */ +typedef enum +{ + QSPI_RSTSC_HW_AUTO = 0x00, /*!< qspi read status by hardware */ + QSPI_RSTSC_SW_ONCE = 0x01 /*!< qspi read status by software */ +} qspi_read_status_conf_type; + +/** + * @brief qspi operate mode type + */ +typedef enum +{ + QSPI_OPERATE_MODE_111 = 0x00, /*!< qspi serial mode */ + QSPI_OPERATE_MODE_112 = 0x01, /*!< qspi dual mode */ + QSPI_OPERATE_MODE_114 = 0x02, /*!< qspi quad mode */ + QSPI_OPERATE_MODE_122 = 0x03, /*!< qspi dual i/o mode */ + QSPI_OPERATE_MODE_144 = 0x04, /*!< qspi quad i/o mode */ + QSPI_OPERATE_MODE_222 = 0x05, /*!< qspi instruction 2-bit mode */ + QSPI_OPERATE_MODE_444 = 0x06 /*!< qspi instruction 4-bit mode(qpi) */ +} qspi_operate_mode_type; + +/** + * @brief qspi clock division type + */ +typedef enum +{ + QSPI_CLK_DIV_2 = 0x00, /*!< qspi clk divide by 2 */ + QSPI_CLK_DIV_4 = 0x01, /*!< qspi clk divide by 4 */ + QSPI_CLK_DIV_6 = 0x02, /*!< qspi clk divide by 6 */ + QSPI_CLK_DIV_8 = 0x03, /*!< qspi clk divide by 8 */ + QSPI_CLK_DIV_3 = 0x04, /*!< qspi clk divide by 3 */ + QSPI_CLK_DIV_5 = 0x05, /*!< qspi clk divide by 5 */ + QSPI_CLK_DIV_10 = 0x06, /*!< qspi clk divide by 10 */ + QSPI_CLK_DIV_12 = 0x07 /*!< qspi clk divide by 12 */ +} qspi_clk_div_type; + +/** + * @brief qspi command port address length type + */ +typedef enum +{ + QSPI_CMD_ADRLEN_0_BYTE = 0x00, /*!< qspi no address */ + QSPI_CMD_ADRLEN_1_BYTE = 0x01, /*!< qspi address length 1 byte */ + QSPI_CMD_ADRLEN_2_BYTE = 0x02, /*!< qspi address length 2 byte */ + QSPI_CMD_ADRLEN_3_BYTE = 0x03, /*!< qspi address length 3 byte */ + QSPI_CMD_ADRLEN_4_BYTE = 0x04 /*!< qspi address length 4 byte */ +} qspi_cmd_adrlen_type; + +/** + * @brief qspi command port instruction length type + */ +typedef enum +{ + QSPI_CMD_INSLEN_0_BYTE = 0x00, /*!< qspi no instruction code */ + QSPI_CMD_INSLEN_1_BYTE = 0x01, /*!< qspi instruction code 1 byte */ + QSPI_CMD_INSLEN_2_BYTE = 0x02 /*!< qspi instruction code 2 byte(repeat) */ +} qspi_cmd_inslen_type; + +/** + * @brief qspi xip r/w address length type + */ +typedef enum +{ + QSPI_XIP_ADDRLEN_3_BYTE = 0x00, /*!< qspi xip address length 3 byte */ + QSPI_XIP_ADDRLEN_4_BYTE = 0x01 /*!< qspi xip address length 4 byte */ +} qspi_xip_addrlen_type; + +/** + * @brief qspi sckout mode type + */ +typedef enum +{ + QSPI_SCK_MODE_0 = 0x00, /*!< qspi sck mode 0 */ + QSPI_SCK_MODE_3 = 0x01 /*!< qspi sck mode 3 */ +} qspi_clk_mode_type; + +/** + * @brief qspi dma tx/rx fifo threshold type + */ +typedef enum +{ + QSPI_DMA_FIFO_THOD_WORD08 = 0x00, /*!< qspi dma fifo threshold 8 words */ + QSPI_DMA_FIFO_THOD_WORD16 = 0x01, /*!< qspi dma fifo threshold 16 words */ + QSPI_DMA_FIFO_THOD_WORD32 = 0x02 /*!< qspi dma fifo threshold 32 words */ +} qspi_dma_fifo_thod_type; + +/** + * @brief qspi cmd type + */ +typedef struct +{ + confirm_state pe_mode_enable; /*!< perfornance enhance mode enable */ + uint8_t pe_mode_operate_code; /*!< performance enhance mode operate code */ + uint8_t instruction_code; /*!< instruction code */ + qspi_cmd_inslen_type instruction_length; /*!< instruction code length */ + uint32_t address_code; /*!< address code */ + qspi_cmd_adrlen_type address_length; /*!< address legnth */ + uint32_t data_counter; /*!< read/write data counter */ + uint8_t second_dummy_cycle_num; /*!< number of second dummy state cycle 0~32 */ + qspi_operate_mode_type operation_mode; /*!< operation mode */ + qspi_read_status_conf_type read_status_config; /*!< config to read status */ + confirm_state read_status_enable; /*!< config to read status */ + confirm_state write_data_enable; /*!< enable to write data */ +} qspi_cmd_type; + +/** + * @brief qspi xip type + */ +typedef struct +{ + uint8_t read_instruction_code; /*!< read instruction code */ + qspi_xip_addrlen_type read_address_length; /*!< read address legnth */ + qspi_operate_mode_type read_operation_mode; /*!< read operation mode */ + uint8_t read_second_dummy_cycle_num; /*!< read number of second dummy state cycle 0~32 */ + uint8_t write_instruction_code; /*!< write instruction code */ + qspi_xip_addrlen_type write_address_length; /*!< write address legnth */ + qspi_operate_mode_type write_operation_mode; /*!< write operation mode */ + uint8_t write_second_dummy_cycle_num; /*!< write number of second dummy state cycle 0~32 */ + qspi_xip_write_sel_type write_select_mode; /*!< write mode d or mode t selection */ + uint8_t write_time_counter; /*!< write count for mode t */ + uint8_t write_data_counter; /*!< write count for mode d */ + qspi_xip_read_sel_type read_select_mode; /*!< read mode d or mode t selection */ + uint8_t read_time_counter; /*!< read count for mode t */ + uint8_t read_data_counter; /*!< read count for mode d */ +} qspi_xip_type; + +/** + * @brief type define qspi register all + */ +typedef struct +{ + /** + * @brief qspi cmd_w0 register, offset:0x00 + */ + union + { + __IO uint32_t cmd_w0; + struct + { + + __IO uint32_t spiadr : 32;/* [31:0] */ + } cmd_w0_bit; + }; + + /** + * @brief qspi cmd_w1 register, offset:0x04 + */ + union + { + __IO uint32_t cmd_w1; + struct + { + __IO uint32_t adrlen : 3; /* [2:0] */ + __IO uint32_t reserved1 : 13;/* [15:3] */ + __IO uint32_t dum2 : 8; /* [23:16] */ + __IO uint32_t inslen : 2; /* [25:24] */ + __IO uint32_t reserved2 : 2; /* [27:26] */ + __IO uint32_t pemen : 1; /* [28] */ + __IO uint32_t reserved3 : 3; /* [31:29] */ + } cmd_w1_bit; + }; + + /** + * @brief qspi cmd_w2 register, offset:0x08 + */ + union + { + __IO uint32_t cmd_w2; + struct + { + __IO uint32_t dcnt : 32;/* [31:0] */ + } cmd_w2_bit; + }; + + /** + * @brief qspi cmd_w3 register, offset:0x0C + */ + union + { + __IO uint32_t cmd_w3; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t wen : 1; /* [1] */ + __IO uint32_t rstsen : 1; /* [2] */ + __IO uint32_t rstsc : 1; /* [3] */ + __IO uint32_t reserved2 : 1; /* [4] */ + __IO uint32_t opmode : 3; /* [7:5] */ + __IO uint32_t reserved3 : 8; /* [15:8] */ + __IO uint32_t pemopc : 8; /* [23:16] */ + __IO uint32_t insc : 8; /* [31:24] */ + } cmd_w3_bit; + }; + + /** + * @brief qspi ctrl register, offset:0x10 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t clkdiv : 3; /* [2:0] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t sckmode : 1; /* [4] */ + __IO uint32_t reserved2 : 2; /* [6:5] */ + __IO uint32_t xipidle : 1; /* [7] */ + __IO uint32_t abort : 1; /* [8] */ + __IO uint32_t reserved3 : 7; /* [15:9] */ + __IO uint32_t busy : 3; /* [18:16] */ + __IO uint32_t xiprcmdf : 1; /* [19] */ + __IO uint32_t xipsel : 1; /* [20] */ + __IO uint32_t keyen : 1; /* [21] */ + __IO uint32_t reserved4 : 10;/* [31:22] */ + } ctrl_bit; + }; + + /** + * @brief qspi actr register, offset:0x14 + */ + union + { + __IO uint32_t actr; + struct + { + __IO uint32_t csdly : 4; /* [3:0] */ + __IO uint32_t reserved1 : 28;/* [31:4] */ + } actr_bit; + }; + + /** + * @brief qspi fifosts register, offset:0x18 + */ + union + { + __IO uint32_t fifosts; + struct + { + __IO uint32_t txfifordy : 1; /* [0] */ + __IO uint32_t rxfifordy : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } fifosts_bit; + }; + + /** + * @brief qspi reserved register, offset:0x1C + */ + __IO uint32_t reserved1; + + /** + * @brief qspi ctrl2 register, offset:0x20 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t dmaen : 1; /* [0] */ + __IO uint32_t cmdie : 1; /* [1] */ + __IO uint32_t reserved1 : 6; /* [7:2] */ + __IO uint32_t txfifo_thod : 2; /* [9:8] */ + __IO uint32_t reserved2 : 2; /* [11:10] */ + __IO uint32_t rxfifo_thod : 2; /* [13:12] */ + __IO uint32_t reserved3 : 18;/* [31:14] */ + } ctrl2_bit; + }; + + /** + * @brief qspi cmdsts register, offset:0x24 + */ + union + { + __IO uint32_t cmdsts; + struct + { + __IO uint32_t cmdsts : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } cmdsts_bit; + }; + + /** + * @brief qspi rsts register, offset:0x28 + */ + union + { + __IO uint32_t rsts; + struct + { + __IO uint32_t spists : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } rsts_bit; + }; + + /** + * @brief qspi fsize register, offset:0x2C + */ + union + { + __IO uint32_t fsize; + struct + { + __IO uint32_t spifsize : 32;/* [31:0] */ + } fsize_bit; + }; + + /** + * @brief qspi xip_cmd_w0 register, offset:0x30 + */ + union + { + __IO uint32_t xip_cmd_w0; + struct + { + __IO uint32_t xipr_dum2 : 8; /* [7:0] */ + __IO uint32_t xipr_opmode : 3; /* [10:8] */ + __IO uint32_t xipr_adrlen : 1; /* [11] */ + __IO uint32_t xipr_insc : 8; /* [19:12] */ + __IO uint32_t reserved1 : 12;/* [31:20] */ + } xip_cmd_w0_bit; + }; + + /** + * @brief qspi xip_cmd_w1 register, offset:0x34 + */ + union + { + __IO uint32_t xip_cmd_w1; + struct + { + __IO uint32_t xipr_dum2 : 8; /* [7:0] */ + __IO uint32_t xipr_opmode : 3; /* [10:8] */ + __IO uint32_t xipr_adrlen : 1; /* [11] */ + __IO uint32_t xipr_insc : 8; /* [19:12] */ + __IO uint32_t reserved1 : 12;/* [31:20] */ + } xip_cmd_w1_bit; + }; + + /** + * @brief qspi xip_cmd_w2 register, offset:0x38 + */ + union + { + __IO uint32_t xip_cmd_w2; + struct + { + __IO uint32_t xipr_dcnt : 6; /* [5:0] */ + __IO uint32_t reserved1 : 2; /* [7:6] */ + __IO uint32_t xipr_tcnt : 7; /* [14:8] */ + __IO uint32_t xipr_sel : 1; /* [15] */ + __IO uint32_t xipw_dcnt : 6; /* [21:16] */ + __IO uint32_t reserved2 : 2; /* [23:22] */ + __IO uint32_t xipw_tcnt : 7; /* [30:24] */ + __IO uint32_t xipw_sel : 1; /* [31] */ + } xip_cmd_w2_bit; + }; + + /** + * @brief qspi xip_cmd_w3 register, offset:0x3C + */ + union + { + __IO uint32_t xip_cmd_w3; + struct + { + __IO uint32_t bypassc : 1; /* [0] */ + __IO uint32_t reserved1 : 2; /* [2:1] */ + __IO uint32_t csts : 1; /* [3] */ + __IO uint32_t reserved2 : 28;/* [31:4] */ + } xip_cmd_w3_bit; + }; + + /** + * @brief qspi reserved register, offset:0x40~4C + */ + __IO uint32_t reserved2[4]; + + /** + * @brief qspi rev register, offset:0x50 + */ + union + { + __IO uint32_t rev; + struct + { + __IO uint32_t rev : 32;/* [31:0] */ + } rev_bit; + }; + + /** + * @brief qspi reserved register, offset:0x54~FC + */ + __IO uint32_t reserved3[43]; + + /** + * @brief qspi dt register, offset:0x100 + */ + union + { + __IO uint8_t dt_u8; + __IO uint16_t dt_u16; + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 32;/* [31:0] */ + } dt_bit; + }; + +} qspi_type; + +/** + * @} + */ + +#define QSPI1 ((qspi_type*)QSPI1_REG_BASE) +#define QSPI2 ((qspi_type*)QSPI2_REG_BASE) + +/** @defgroup QSPI_exported_functions + * @{ + */ + +void qspi_encryption_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_sck_mode_set(qspi_type* qspi_x, qspi_clk_mode_type new_mode); +void qspi_clk_division_set(qspi_type* qspi_x, qspi_clk_div_type new_clkdiv); +void qspi_xip_cache_bypass_set(qspi_type* qspi_x, confirm_state new_state); +void qspi_interrupt_enable(qspi_type* qspi_x, confirm_state new_state); +flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag); +void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag); +void qspi_dma_rx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold); +void qspi_dma_tx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold); +void qspi_dma_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_busy_config(qspi_type* qspi_x, qspi_busy_pos_type busy_pos); +void qspi_xip_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_cmd_operation_kick(qspi_type* qspi_x, qspi_cmd_type* qspi_cmd_struct); +void qspi_xip_init(qspi_type* qspi_x, qspi_xip_type* xip_init_struct); +uint8_t qspi_byte_read(qspi_type* qspi_x); +uint16_t qspi_half_word_read(qspi_type* qspi_x); +uint32_t qspi_word_read(qspi_type* qspi_x); +void qspi_word_write(qspi_type* qspi_x, uint32_t value); +void qspi_half_word_write(qspi_type* qspi_x, uint16_t value); +void qspi_byte_write(qspi_type* qspi_x, uint8_t value); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h new file mode 100644 index 0000000000..3fdf033095 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h @@ -0,0 +1,323 @@ +/** + ************************************************************************** + * @file at32f435_437_scfg.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 system config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SCFG_H +#define __AT32F435_437_SCFG_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SCFG + * @{ + */ + +#define SCFG_REG(value) PERIPH_REG(SCFG_BASE, value) +#define SCFG_REG_BIT(value) PERIPH_REG_BIT(value) + +/** @defgroup SCFG_exported_types + * @{ + */ + +/** + * @brief scfg xmc addres mapping swap type + */ +typedef enum +{ + SCFG_XMC_SWAP_NONE = 0x00, /* no swap */ + SCFG_XMC_SWAP_MODE1 = 0x01, /* sdram 0x60000000 and 0x70000000, nor psram sram nand2 0xC00000000 and 0xD0000000 */ + SCFG_XMC_SWAP_MODE2 = 0x02, /* qspi2 0x80000000, nand3 0xB0000000 */ + SCFG_XMC_SWAP_MODE3 = 0x03 /* sdram 0x60000000 and 0x70000000, nor psram sram nand2 0xC00000000 and 0xD0000000, qspi2 0x80000000, nand3 0xB0000000 */ +} scfg_xmc_swap_type; + +/** + * @brief scfg infrared modulation signal source selecting type + */ +typedef enum +{ + SCFG_IR_SOURCE_TMR10 = 0x00, /* infrared signal source select tmr10 */ + SCFG_IR_SOURCE_USART1 = 0x01, /* infrared signal source select usart1 */ + SCFG_IR_SOURCE_USART2 = 0x02 /* infrared signal source select usart2 */ +} scfg_ir_source_type; + +/** + * @brief scfg infrared output polarity selecting type + */ +typedef enum +{ + SCFG_IR_POLARITY_NO_AFFECTE = 0x00, /* infrared output polarity no affecte */ + SCFG_IR_POLARITY_REVERSE = 0x01 /* infrared output polarity reverse */ +} scfg_ir_polarity_type; + +/** + * @brief scfg memory address mapping selecting type + */ +typedef enum +{ + SCFG_MEM_MAP_MAIN_MEMORY = 0x00, /* 0x00000000 address mapping from main memory */ + SCFG_MEM_MAP_BOOT_MEMORY = 0x01, /* 0x00000000 address mapping from boot memory */ + SCFG_MEM_MAP_XMC_BANK1 = 0x02, /* 0x00000000 address mapping from xmc bank1 */ + SCFG_MEM_MAP_INTERNAL_SRAM = 0x03, /* 0x00000000 address mapping from internal sram */ + SCFG_MEM_MAP_XMC_SDRAM_BANK1 = 0x04 /* 0x00000000 address mapping from xmc sdram bank1 */ +} scfg_mem_map_type; + +/** + * @brief scfg pin source type + */ +typedef enum +{ + SCFG_PINS_SOURCE0 = 0x00, + SCFG_PINS_SOURCE1 = 0x01, + SCFG_PINS_SOURCE2 = 0x02, + SCFG_PINS_SOURCE3 = 0x03, + SCFG_PINS_SOURCE4 = 0x04, + SCFG_PINS_SOURCE5 = 0x05, + SCFG_PINS_SOURCE6 = 0x06, + SCFG_PINS_SOURCE7 = 0x07, + SCFG_PINS_SOURCE8 = 0x08, + SCFG_PINS_SOURCE9 = 0x09, + SCFG_PINS_SOURCE10 = 0x0A, + SCFG_PINS_SOURCE11 = 0x0B, + SCFG_PINS_SOURCE12 = 0x0C, + SCFG_PINS_SOURCE13 = 0x0D, + SCFG_PINS_SOURCE14 = 0x0E, + SCFG_PINS_SOURCE15 = 0x0F +} scfg_pins_source_type; + +/** + * @brief gpio port source type + */ +typedef enum +{ + SCFG_PORT_SOURCE_GPIOA = 0x00, + SCFG_PORT_SOURCE_GPIOB = 0x01, + SCFG_PORT_SOURCE_GPIOC = 0x02, + SCFG_PORT_SOURCE_GPIOD = 0x03, + SCFG_PORT_SOURCE_GPIOE = 0x04, + SCFG_PORT_SOURCE_GPIOF = 0x05, + SCFG_PORT_SOURCE_GPIOG = 0x06, + SCFG_PORT_SOURCE_GPIOH = 0x07 +} scfg_port_source_type; + +/** + * @brief scfg emac interface selecting type + */ +typedef enum +{ + SCFG_EMAC_SELECT_MII = 0x00, /* emac interface select mii mode */ + SCFG_EMAC_SELECT_RMII = 0x01 /* emac interface select rmii mode */ +} scfg_emac_interface_type; + +/** + * @brief scfg ultra high sourcing/sinking strength pins type + */ +typedef enum +{ + SCFG_ULTRA_DRIVEN_PB3 = MAKE_VALUE(0x2C, 0), + SCFG_ULTRA_DRIVEN_PB9 = MAKE_VALUE(0x2C, 1), + SCFG_ULTRA_DRIVEN_PB10 = MAKE_VALUE(0x2C, 2), + SCFG_ULTRA_DRIVEN_PD12 = MAKE_VALUE(0x2C, 5), + SCFG_ULTRA_DRIVEN_PD13 = MAKE_VALUE(0x2C, 6), + SCFG_ULTRA_DRIVEN_PD14 = MAKE_VALUE(0x2C, 7), + SCFG_ULTRA_DRIVEN_PD15 = MAKE_VALUE(0x2C, 8), + SCFG_ULTRA_DRIVEN_PF14 = MAKE_VALUE(0x2C, 9), + SCFG_ULTRA_DRIVEN_PF15 = MAKE_VALUE(0x2C, 10) +} scfg_ultra_driven_pins_type; + +/** + * @brief type define system config register all + */ +typedef struct +{ + /** + * @brief scfg cfg1 register, offset:0x00 + */ + union + { + __IO uint32_t cfg1; + struct + { + __IO uint32_t mem_map_sel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 2; /* [4:3] */ + __IO uint32_t ir_pol : 1; /* [5] */ + __IO uint32_t ir_src_sel : 2; /* [7:6] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t swap_xmc : 2; /* [11:10] */ + __IO uint32_t reserved3 : 20;/* [31:12] */ + } cfg1_bit; + }; + + /** + * @brief scfg cfg2 register, offset:0x04 + */ + union + { + __IO uint32_t cfg2; + struct + { + __IO uint32_t reserved1 : 23;/* [22:0] */ + __IO uint32_t mii_rmii_sel : 1; /* [23] */ + __IO uint32_t reserved2 : 8; /* [31:24] */ + } cfg2_bit; + }; + + /** + * @brief scfg exintc1 register, offset:0x08 + */ + union + { + __IO uint32_t exintc1; + struct + { + __IO uint32_t exint0 : 4; /* [3:0] */ + __IO uint32_t exint1 : 4; /* [7:4] */ + __IO uint32_t exint2 : 4; /* [11:8] */ + __IO uint32_t exint3 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc1_bit; + }; + + /** + * @brief scfg exintc2 register, offset:0x0C + */ + union + { + __IO uint32_t exintc2; + struct + { + __IO uint32_t exint4 : 4; /* [3:0] */ + __IO uint32_t exint5 : 4; /* [7:4] */ + __IO uint32_t exint6 : 4; /* [11:8] */ + __IO uint32_t exint7 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc2_bit; + }; + + /** + * @brief scfg exintc3 register, offset:0x10 + */ + union + { + __IO uint32_t exintc3; + struct + { + __IO uint32_t exint8 : 4; /* [3:0] */ + __IO uint32_t exint9 : 4; /* [7:4] */ + __IO uint32_t exint10 : 4; /* [11:8] */ + __IO uint32_t exint11 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc3_bit; + }; + + /** + * @brief scfg exintc4 register, offset:0x14 + */ + union + { + __IO uint32_t exintc4; + struct + { + __IO uint32_t exint12 : 4; /* [3:0] */ + __IO uint32_t exint13 : 4; /* [7:4] */ + __IO uint32_t exint14 : 4; /* [11:8] */ + __IO uint32_t exint15 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc4_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x18~0x28 + */ + __IO uint32_t reserved1[5]; + + /** + * @brief scfg uhdrv register, offset:0x2C + */ + union + { + __IO uint32_t uhdrv; + struct + { + __IO uint32_t pb3_uh : 1; /* [0] */ + __IO uint32_t pb9_uh : 1; /* [1] */ + __IO uint32_t pb10_uh : 1; /* [2] */ + __IO uint32_t reserved1 : 2; /* [4:3] */ + __IO uint32_t pd12_uh : 1; /* [5] */ + __IO uint32_t pd13_uh : 1; /* [6] */ + __IO uint32_t pd14_uh : 1; /* [7] */ + __IO uint32_t pd15_uh : 1; /* [8] */ + __IO uint32_t pf14_uh : 1; /* [9] */ + __IO uint32_t pf15_uh : 1; /* [10] */ + __IO uint32_t reserved2 : 21;/* [31:11] */ + } uhdrv_bit; + }; + +} scfg_type; + +/** + * @} + */ + +#define SCFG ((scfg_type *) SCFG_BASE) + +/** @defgroup SCFG_exported_functions + * @{ + */ + +void scfg_reset(void); +void scfg_xmc_mapping_swap_set(scfg_xmc_swap_type xmc_swap); +void scfg_infrared_config(scfg_ir_source_type source, scfg_ir_polarity_type polarity); +void scfg_mem_map_set(scfg_mem_map_type mem_map); +void scfg_emac_interface_set(scfg_emac_interface_type mode); +void scfg_exint_line_config(scfg_port_source_type port_source, scfg_pins_source_type pin_source); +void scfg_pins_ultra_driven_enable(scfg_ultra_driven_pins_type value, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h new file mode 100644 index 0000000000..5c4180bf83 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h @@ -0,0 +1,624 @@ +/** + ************************************************************************** + * @file at32f435_437_sdio.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 sdio header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SDIO_H +#define __AT32F435_437_SDIO_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/** @defgroup SDIO_interrupts_definition + * @brief sdio interrupt + * @{ + */ + +#define SDIO_CMDFAIL_INT ((uint32_t)0x00000001) /*!< command response received check failed interrupt */ +#define SDIO_DTFAIL_INT ((uint32_t)0x00000002) /*!< data block sent/received check failed interrupt */ +#define SDIO_CMDTIMEOUT_INT ((uint32_t)0x00000004) /*!< command response timerout interrupt */ +#define SDIO_DTTIMEOUT_INT ((uint32_t)0x00000008) /*!< data timeout interrupt */ +#define SDIO_TXERRU_INT ((uint32_t)0x00000010) /*!< transmit underrun error interrupt */ +#define SDIO_RXERRO_INT ((uint32_t)0x00000020) /*!< received overrun error interrupt */ +#define SDIO_CMDRSPCMPL_INT ((uint32_t)0x00000040) /*!< command response received interrupt */ +#define SDIO_CMDCMPL_INT ((uint32_t)0x00000080) /*!< command sent interrupt */ +#define SDIO_DTCMP_INT ((uint32_t)0x00000100) /*!< data sent interrupt */ +#define SDIO_SBITERR_INT ((uint32_t)0x00000200) /*!< start bit not detected on data bus interrupt */ +#define SDIO_DTBLKCMPL_INT ((uint32_t)0x00000400) /*!< data block sent/received interrupt */ +#define SDIO_DOCMD_INT ((uint32_t)0x00000800) /*!< command transfer in progress interrupt */ +#define SDIO_DOTX_INT ((uint32_t)0x00001000) /*!< data transmit in progress interrupt */ +#define SDIO_DORX_INT ((uint32_t)0x00002000) /*!< data receive in progress interrupt */ +#define SDIO_TXBUFH_INT ((uint32_t)0x00004000) /*!< transmit buf half empty interrupt */ +#define SDIO_RXBUFH_INT ((uint32_t)0x00008000) /*!< receive buf half full interrupt */ +#define SDIO_TXBUFF_INT ((uint32_t)0x00010000) /*!< transmit buf full interrupt */ +#define SDIO_RXBUFF_INT ((uint32_t)0x00020000) /*!< receive buf full interrupt */ +#define SDIO_TXBUFE_INT ((uint32_t)0x00040000) /*!< transmit buf empty interrupt */ +#define SDIO_RXBUFE_INT ((uint32_t)0x00080000) /*!< receive buf empty interrupt */ +#define SDIO_TXBUF_INT ((uint32_t)0x00100000) /*!< data available in transmit interrupt */ +#define SDIO_RXBUF_INT ((uint32_t)0x00200000) /*!< data available in receive interrupt */ +#define SDIO_SDIOIF_INT ((uint32_t)0x00400000) /*!< sdio interface received interrupt */ + +/** + * @} + */ + +/** @defgroup SDIO_flags_definition + * @brief sdio flag + * @{ + */ + +#define SDIO_CMDFAIL_FLAG ((uint32_t)0x00000001) /*!< command response received check failed flag */ +#define SDIO_DTFAIL_FLAG ((uint32_t)0x00000002) /*!< data block sent/received check failed flag */ +#define SDIO_CMDTIMEOUT_FLAG ((uint32_t)0x00000004) /*!< command response timerout flag */ +#define SDIO_DTTIMEOUT_FLAG ((uint32_t)0x00000008) /*!< data timeout flag */ +#define SDIO_TXERRU_FLAG ((uint32_t)0x00000010) /*!< transmit underrun error flag */ +#define SDIO_RXERRO_FLAG ((uint32_t)0x00000020) /*!< received overrun error flag */ +#define SDIO_CMDRSPCMPL_FLAG ((uint32_t)0x00000040) /*!< command response received flag */ +#define SDIO_CMDCMPL_FLAG ((uint32_t)0x00000080) /*!< command sent flag */ +#define SDIO_DTCMPL_FLAG ((uint32_t)0x00000100) /*!< data sent flag */ +#define SDIO_SBITERR_FLAG ((uint32_t)0x00000200) /*!< start bit not detected on data bus flag */ +#define SDIO_DTBLKCMPL_FLAG ((uint32_t)0x00000400) /*!< data block sent/received flag */ +#define SDIO_DOCMD_FLAG ((uint32_t)0x00000800) /*!< command transfer in progress flag */ +#define SDIO_DOTX_FLAG ((uint32_t)0x00001000) /*!< data transmit in progress flag */ +#define SDIO_DORX_FLAG ((uint32_t)0x00002000) /*!< data receive in progress flag */ +#define SDIO_TXBUFH_FLAG ((uint32_t)0x00004000) /*!< transmit buf half empty flag */ +#define SDIO_RXBUFH_FLAG ((uint32_t)0x00008000) /*!< receive buf half full flag */ +#define SDIO_TXBUFF_FLAG ((uint32_t)0x00010000) /*!< transmit buf full flag */ +#define SDIO_RXBUFF_FLAG ((uint32_t)0x00020000) /*!< receive buf full flag */ +#define SDIO_TXBUFE_FLAG ((uint32_t)0x00040000) /*!< transmit buf empty flag */ +#define SDIO_RXBUFE_FLAG ((uint32_t)0x00080000) /*!< receive buf empty flag */ +#define SDIO_TXBUF_FLAG ((uint32_t)0x00100000) /*!< data available in transmit flag */ +#define SDIO_RXBUF_FLAG ((uint32_t)0x00200000) /*!< data available in receive flag */ +#define SDIO_SDIOIF_FLAG ((uint32_t)0x00400000) /*!< sdio interface received flag */ + +/** + * @} + */ + +/** @defgroup SDIO_exported_types + * @{ + */ + +/** + * @brief sdio power state + */ +typedef enum +{ + SDIO_POWER_OFF = 0x00, /*!< power-off, clock to card is stopped */ + SDIO_POWER_ON = 0x03 /*!< power-on, the card is clocked */ +} sdio_power_state_type; + +/** + * @brief sdio edge phase + */ +typedef enum +{ + SDIO_CLOCK_EDGE_RISING = 0x00, /*!< sdio bus clock generated on the rising edge of the master clock */ + SDIO_CLOCK_EDGE_FALLING = 0x01 /*!< sdio bus clock generated on the falling edge of the master clock */ +} sdio_edge_phase_type; + +/** + * @brief sdio bus width + */ +typedef enum +{ + SDIO_BUS_WIDTH_D1 = 0x00, /*!< sdio wide bus select 1-bit */ + SDIO_BUS_WIDTH_D4 = 0x01, /*!< sdio wide bus select 4-bit */ + SDIO_BUS_WIDTH_D8 = 0x02 /*!< sdio wide bus select 8-bit */ +} sdio_bus_width_type; + +/** + * @brief sdio response type + */ +typedef enum +{ + SDIO_RESPONSE_NO = 0x00, /*!< no response */ + SDIO_RESPONSE_SHORT = 0x01, /*!< short response */ + SDIO_RESPONSE_LONG = 0x03 /*!< long response */ +} sdio_reponse_type; + +/** + * @brief sdio wait type + */ +typedef enum +{ + SDIO_WAIT_FOR_NO = 0x00, /*!< no wait */ + SDIO_WAIT_FOR_INT = 0x01, /*!< wait interrupt request */ + SDIO_WAIT_FOR_PEND = 0x02 /*!< wait end of transfer */ +} sdio_wait_type; + +/** + * @brief sdio response register index + */ +typedef enum +{ + SDIO_RSP1_INDEX = 0x00, /*!< response index 1, corresponding to sdio_rsp register 1 */ + SDIO_RSP2_INDEX = 0x01, /*!< response index 2, corresponding to sdio_rsp register 2 */ + SDIO_RSP3_INDEX = 0x02, /*!< response index 3, corresponding to sdio_rsp register 3 */ + SDIO_RSP4_INDEX = 0x03 /*!< response index 4, corresponding to sdio_rsp register 4 */ +} sdio_rsp_index_type; + +/** + * @brief sdio data block size + */ +typedef enum +{ + SDIO_DATA_BLOCK_SIZE_1B = 0x00, /*!< data block size 1 byte */ + SDIO_DATA_BLOCK_SIZE_2B = 0x01, /*!< data block size 2 bytes */ + SDIO_DATA_BLOCK_SIZE_4B = 0x02, /*!< data block size 4 bytes */ + SDIO_DATA_BLOCK_SIZE_8B = 0x03, /*!< data block size 8 bytes */ + SDIO_DATA_BLOCK_SIZE_16B = 0x04, /*!< data block size 16 bytes */ + SDIO_DATA_BLOCK_SIZE_32B = 0x05, /*!< data block size 32 bytes */ + SDIO_DATA_BLOCK_SIZE_64B = 0x06, /*!< data block size 64 bytes */ + SDIO_DATA_BLOCK_SIZE_128B = 0x07, /*!< data block size 128 bytes */ + SDIO_DATA_BLOCK_SIZE_256B = 0x08, /*!< data block size 256 bytes */ + SDIO_DATA_BLOCK_SIZE_512B = 0x09, /*!< data block size 512 bytes */ + SDIO_DATA_BLOCK_SIZE_1024B = 0x0A, /*!< data block size 1024 bytes */ + SDIO_DATA_BLOCK_SIZE_2048B = 0x0B, /*!< data block size 2048 bytes */ + SDIO_DATA_BLOCK_SIZE_4096B = 0x0C, /*!< data block size 4096 bytes */ + SDIO_DATA_BLOCK_SIZE_8192B = 0x0D, /*!< data block size 8192 bytes */ + SDIO_DATA_BLOCK_SIZE_16384B = 0x0E /*!< data block size 16384 bytes */ +} sdio_block_size_type; + +/** + * @brief sdio data transfer mode + */ +typedef enum +{ + SDIO_DATA_BLOCK_TRANSFER = 0x00, /*!< the sdio block transfer mode */ + SDIO_DATA_STREAM_TRANSFER = 0x01 /*!< the sdio stream transfer mode */ +} sdio_transfer_mode_type; + +/** + * @brief sdio data transfer direction + */ +typedef enum +{ + SDIO_DATA_TRANSFER_TO_CARD = 0x00, /*!< the sdio controller write */ + SDIO_DATA_TRANSFER_TO_CONTROLLER = 0x01 /*!< the sdio controller read */ +} sdio_transfer_direction_type; + +/** + * @brief sdio read wait mode + */ +typedef enum +{ + SDIO_READ_WAIT_CONTROLLED_BY_D2 = 0x00, /*!< the sdio read wait on data2 line */ + SDIO_READ_WAIT_CONTROLLED_BY_CK = 0x01 /*!< the sdio read wait on clock line */ +} sdio_read_wait_mode_type; + +/** + * @brief sdio command structure + */ +typedef struct +{ + uint32_t argument; /*!< the sdio command argument is sent to a card as part of command message */ + uint8_t cmd_index; /*!< the sdio command index */ + sdio_reponse_type rsp_type; /*!< the sdio response type */ + sdio_wait_type wait_type; /*!< the sdio wait for interrupt request is enabled or disable */ +} sdio_command_struct_type; + +/** + * @brief sdio data structure + */ +typedef struct +{ + uint32_t timeout; /*!< the sdio data timeout period in car bus clock periods */ + uint32_t data_length; /*!< the sdio data length */ + sdio_block_size_type block_size; /*!< the sdio data block size of block transfer mode */ + sdio_transfer_mode_type transfer_mode; /*!< the sdio transfer mode, block or stream */ + sdio_transfer_direction_type transfer_direction; /*!< the sdio data transfer direction */ +} sdio_data_struct_type; + +/** + * @brief type define sdio register all + */ +typedef struct +{ + /** + * @brief sdio pwrctrl register, offset:0x00 + */ + union + { + __IO uint32_t pwrctrl; + struct + { + __IO uint32_t ps : 2; /* [1:0] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } pwrctrl_bit; + }; + + /** + * @brief sdio clkctrl register, offset:0x04 + */ + union + { + __IO uint32_t clkctrl; + struct + { + __IO uint32_t clkdiv_l : 8; /* [7:0] */ + __IO uint32_t clkoen : 1; /* [8] */ + __IO uint32_t pwrsven : 1; /* [9] */ + __IO uint32_t bypsen : 1; /* [10] */ + __IO uint32_t busws : 2; /* [12:11] */ + __IO uint32_t clkegs : 1; /* [13] */ + __IO uint32_t hfcen : 1; /* [14] */ + __IO uint32_t clkdiv_h : 2; /* [16:15] */ + __IO uint32_t reserved1 : 15;/* [31:17] */ + } clkctrl_bit; + }; + + /** + * @brief sdio argu register, offset:0x08 + */ + union + { + __IO uint32_t argu; + struct + { + __IO uint32_t argu : 32;/* [31:0] */ + } argu_bit; + }; + + /** + * @brief sdio cmdctrl register, offset:0x0C + */ + union + { + __IO uint32_t cmdctrl; + struct + { + __IO uint32_t cmdidx : 6; /* [5:0] */ + __IO uint32_t rspwt : 2; /* [7:6] */ + __IO uint32_t intwt : 1; /* [8] */ + __IO uint32_t pndwt : 1; /* [9] */ + __IO uint32_t ccsmen : 1; /* [10] */ + __IO uint32_t iosusp : 1; /* [11] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } cmdctrl_bit; + }; + + /** + * @brief sdio rspcmd register, offset:0x10 + */ + union + { + __IO uint32_t rspcmd; + struct + { + __IO uint32_t rspcmd : 6; /* [5:0] */ + __IO uint32_t reserved1 : 26;/* [31:6] */ + } rspcmd_bit; + }; + + /** + * @brief sdio rsp1 register, offset:0x14 + */ + union + { + __IO uint32_t rsp1; + struct + { + __IO uint32_t cardsts1 : 32;/* [31:0] */ + } rsp1_bit; + }; + + /** + * @brief sdio rsp2 register, offset:0x18 + */ + union + { + __IO uint32_t rsp2; + struct + { + __IO uint32_t cardsts2 : 32;/* [31:0] */ + } rsp2_bit; + }; + + /** + * @brief sdio rsp3 register, offset:0x1C + */ + union + { + __IO uint32_t rsp3; + struct + { + __IO uint32_t cardsts3 : 32;/* [31:0] */ + } rsp3_bit; + }; + + /** + * @brief sdio rsp4 register, offset:0x20 + */ + union + { + __IO uint32_t rsp4; + struct + { + __IO uint32_t cardsts4 : 32;/* [31:0] */ + } rsp4_bit; + }; + + /** + * @brief sdio dttmr register, offset:0x24 + */ + union + { + __IO uint32_t dttmr; + struct + { + __IO uint32_t timeout : 32;/* [31:0] */ + } dttmr_bit; + }; + + /** + * @brief sdio dtlen register, offset:0x28 + */ + union + { + __IO uint32_t dtlen; + struct + { + __IO uint32_t dtlen : 25;/* [24:0] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } dtlen_bit; + }; + + /** + * @brief sdio dtctrl register, offset:0x2C + */ + union + { + __IO uint32_t dtctrl; + struct + { + __IO uint32_t tfren : 1; /* [0] */ + __IO uint32_t tfrdir : 1; /* [1] */ + __IO uint32_t tfrmode : 1; /* [2] */ + __IO uint32_t dmaen : 1; /* [3] */ + __IO uint32_t blksize : 4; /* [7:4] */ + __IO uint32_t rdwtstart : 1; /* [8] */ + __IO uint32_t rdwtstop : 1; /* [9] */ + __IO uint32_t rdwtmode : 1; /* [10] */ + __IO uint32_t ioen : 1; /* [11] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } dtctrl_bit; + }; + + /** + * @brief sdio dtcnt register, offset:0x30 + */ + union + { + __IO uint32_t dtcnt; + struct + { + __IO uint32_t cnt : 25;/* [24:0] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } dtcnt_bit; + }; + + /** + * @brief sdio sts register, offset:0x34 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t cmdfail : 1; /* [0] */ + __IO uint32_t dtfail : 1; /* [1] */ + __IO uint32_t cmdtimeout : 1; /* [2] */ + __IO uint32_t dttimeout : 1; /* [3] */ + __IO uint32_t txerru : 1; /* [4] */ + __IO uint32_t rxerro : 1; /* [5] */ + __IO uint32_t cmdrspcmpl : 1; /* [6] */ + __IO uint32_t cmdcmpl : 1; /* [7] */ + __IO uint32_t dtcmpl : 1; /* [8] */ + __IO uint32_t sbiterr : 1; /* [9] */ + __IO uint32_t dtblkcmpl : 1; /* [10] */ + __IO uint32_t docmd : 1; /* [11] */ + __IO uint32_t dotx : 1; /* [12] */ + __IO uint32_t dorx : 1; /* [13] */ + __IO uint32_t txbufh : 1; /* [14] */ + __IO uint32_t rxbufh : 1; /* [15] */ + __IO uint32_t txbuff : 1; /* [16] */ + __IO uint32_t rxbuff : 1; /* [17] */ + __IO uint32_t txbufe : 1; /* [18] */ + __IO uint32_t rxbufe : 1; /* [19] */ + __IO uint32_t txbuf : 1; /* [20] */ + __IO uint32_t rxbuf : 1; /* [21] */ + __IO uint32_t ioif : 1; /* [22] */ + __IO uint32_t reserved1 : 9; /* [31:23] */ + } sts_bit; + }; + + /** + * @brief sdio intclr register, offset:0x38 + */ + union + { + __IO uint32_t intclr; + struct + { + __IO uint32_t cmdfail : 1; /* [0] */ + __IO uint32_t dtfail : 1; /* [1] */ + __IO uint32_t cmdtimeout : 1; /* [2] */ + __IO uint32_t dttimeout : 1; /* [3] */ + __IO uint32_t txerru : 1; /* [4] */ + __IO uint32_t rxerro : 1; /* [5] */ + __IO uint32_t cmdrspcmpl : 1; /* [6] */ + __IO uint32_t cmdcmpl : 1; /* [7] */ + __IO uint32_t dtcmpl : 1; /* [8] */ + __IO uint32_t sbiterr : 1; /* [9] */ + __IO uint32_t dtblkcmpl : 1; /* [10] */ + __IO uint32_t reserved1 : 11;/* [21:11] */ + __IO uint32_t ioif : 1; /* [22] */ + __IO uint32_t reserved2 : 9; /* [31:23] */ + } intclr_bit; + }; + + /** + * @brief sdio inten register, offset:0x3C + */ + union + { + __IO uint32_t inten; + struct + { + __IO uint32_t cmdfailien : 1; /* [0] */ + __IO uint32_t dtfailien : 1; /* [1] */ + __IO uint32_t cmdtimeoutien : 1; /* [2] */ + __IO uint32_t dttimeoutien : 1; /* [3] */ + __IO uint32_t txerruien : 1; /* [4] */ + __IO uint32_t rxerroien : 1; /* [5] */ + __IO uint32_t cmdrspcmplien : 1; /* [6] */ + __IO uint32_t cmdcmplien : 1; /* [7] */ + __IO uint32_t dtcmplien : 1; /* [8] */ + __IO uint32_t sbiterrien : 1; /* [9] */ + __IO uint32_t dtblkcmplien : 1; /* [10] */ + __IO uint32_t docmdien : 1; /* [11] */ + __IO uint32_t dotxien : 1; /* [12] */ + __IO uint32_t dorxien : 1; /* [13] */ + __IO uint32_t txbufhien : 1; /* [14] */ + __IO uint32_t rxbufhien : 1; /* [15] */ + __IO uint32_t txbuffien : 1; /* [16] */ + __IO uint32_t rxbuffien : 1; /* [17] */ + __IO uint32_t txbufeien : 1; /* [18] */ + __IO uint32_t rxbufeien : 1; /* [19] */ + __IO uint32_t txbufien : 1; /* [20] */ + __IO uint32_t rxbufien : 1; /* [21] */ + __IO uint32_t ioifien : 1; /* [22] */ + __IO uint32_t reserved1 : 9; /* [31:23] */ + } inten_bit; + }; + + /** + * @brief sdio reserved1 register, offset:0x40~0x44 + */ + __IO uint32_t reserved1[2]; + + /** + * @brief sdio bufcnt register, offset:0x48 + */ + union + { + __IO uint32_t bufcnt; + struct + { + __IO uint32_t cnt : 24;/* [23:0] */ + __IO uint32_t reserved1 : 8; /* [31:24] */ + } bufcnt_bit; + }; + + /** + * @brief sdio reserved2 register, offset:0x4C~0x7C + */ + __IO uint32_t reserved2[13]; + + /** + * @brief sdio buf register, offset:0x80 + */ + union + { + __IO uint32_t buf; + struct + { + __IO uint32_t dt : 32;/* [31:0] */ + } buf_bit; + }; + +} sdio_type; + +/** + * @} + */ + +#define SDIO1 ((sdio_type *) SDIO1_BASE) +#define SDIO2 ((sdio_type *) SDIO2_BASE) + +/** @defgroup SDIO_exported_functions + * @{ + */ + +void sdio_reset(sdio_type *sdio_x); +void sdio_power_set(sdio_type *sdio_x, sdio_power_state_type power_state); +sdio_power_state_type sdio_power_status_get(sdio_type *sdio_x); +void sdio_clock_config(sdio_type *sdio_x, uint16_t clk_div, sdio_edge_phase_type clk_edg); +void sdio_bus_width_config(sdio_type *sdio_x, sdio_bus_width_type width); +void sdio_clock_bypass(sdio_type *sdio_x, confirm_state new_state); +void sdio_power_saving_mode_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_flow_control_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_clock_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_dma_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_interrupt_enable(sdio_type *sdio_x, uint32_t int_opt, confirm_state new_state); +flag_status sdio_flag_get(sdio_type *sdio_x, uint32_t flag); +void sdio_flag_clear(sdio_type *sdio_x, uint32_t flag); +void sdio_command_config(sdio_type *sdio_x, sdio_command_struct_type *command_struct); +void sdio_command_state_machine_enable(sdio_type *sdio_x, confirm_state new_state); +uint8_t sdio_command_response_get(sdio_type *sdio_x); +uint32_t sdio_response_get(sdio_type *sdio_x, sdio_rsp_index_type reg_index); +void sdio_data_config(sdio_type *sdio_x, sdio_data_struct_type *data_struct); +void sdio_data_state_machine_enable(sdio_type *sdio_x, confirm_state new_state); +uint32_t sdio_data_counter_get(sdio_type *sdio_x); +uint32_t sdio_data_read(sdio_type *sdio_x); +uint32_t sdio_buffer_counter_get(sdio_type *sdio_x); +void sdio_data_write(sdio_type *sdio_x, uint32_t data); +void sdio_read_wait_mode_set(sdio_type *sdio_x, sdio_read_wait_mode_type mode); +void sdio_read_wait_start(sdio_type *sdio_x, confirm_state new_state); +void sdio_read_wait_stop(sdio_type *sdio_x, confirm_state new_state); +void sdio_io_function_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_io_suspend_command_set(sdio_type *sdio_x, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h new file mode 100644 index 0000000000..bba723a86f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h @@ -0,0 +1,505 @@ +/** + ************************************************************************** + * @file at32f435_437_spi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 spi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SPI_H +#define __AT32F435_437_SPI_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/** + * @defgroup SPI_I2S_flags_definition + * @brief spi i2s flag + * @{ + */ + +#define SPI_I2S_RDBF_FLAG 0x0001 /*!< spi or i2s receive data buffer full flag */ +#define SPI_I2S_TDBE_FLAG 0x0002 /*!< spi or i2s transmit data buffer empty flag */ +#define I2S_ACS_FLAG 0x0004 /*!< i2s audio channel state flag */ +#define I2S_TUERR_FLAG 0x0008 /*!< i2s transmitter underload error flag */ +#define SPI_CCERR_FLAG 0x0010 /*!< spi crc calculation error flag */ +#define SPI_MMERR_FLAG 0x0020 /*!< spi master mode error flag */ +#define SPI_I2S_ROERR_FLAG 0x0040 /*!< spi or i2s receiver overflow error flag */ +#define SPI_I2S_BF_FLAG 0x0080 /*!< spi or i2s busy flag */ +#define SPI_CSPAS_FLAG 0x0100 /*!< spi cs pulse abnormal setting fiag */ + +/** + * @} + */ + +/** + * @defgroup SPI_I2S_interrupts_definition + * @brief spi i2s interrupt + * @{ + */ + +#define SPI_I2S_ERROR_INT 0x0020 /*!< error interrupt */ +#define SPI_I2S_RDBF_INT 0x0040 /*!< receive data buffer full interrupt */ +#define SPI_I2S_TDBE_INT 0x0080 /*!< transmit data buffer empty interrupt */ + +/** + * @} + */ + +/** @defgroup SPI_exported_types + * @{ + */ + +/** + * @brief spi frame bit num type + */ +typedef enum +{ + SPI_FRAME_8BIT = 0x00, /*!< 8-bit data frame format */ + SPI_FRAME_16BIT = 0x01 /*!< 16-bit data frame format */ +} spi_frame_bit_num_type; + +/** + * @brief spi master/slave mode type + */ +typedef enum +{ + SPI_MODE_SLAVE = 0x00, /*!< select as slave mode */ + SPI_MODE_MASTER = 0x01 /*!< select as master mode */ +} spi_master_slave_mode_type; + +/** + * @brief spi clock polarity (clkpol) type + */ +typedef enum +{ + SPI_CLOCK_POLARITY_LOW = 0x00, /*!< sck keeps low at idle state */ + SPI_CLOCK_POLARITY_HIGH = 0x01 /*!< sck keeps high at idle state */ +} spi_clock_polarity_type; + +/** + * @brief spi clock phase (clkpha) type + */ +typedef enum +{ + SPI_CLOCK_PHASE_1EDGE = 0x00, /*!< data capture start from the first clock edge */ + SPI_CLOCK_PHASE_2EDGE = 0x01 /*!< data capture start from the second clock edge */ +} spi_clock_phase_type; + +/** + * @brief spi cs mode type + */ +typedef enum +{ + SPI_CS_HARDWARE_MODE = 0x00, /*!< cs is hardware mode */ + SPI_CS_SOFTWARE_MODE = 0x01 /*!< cs is software mode */ +} spi_cs_mode_type; + +/** + * @brief spi master clock frequency division type + */ +typedef enum +{ + SPI_MCLK_DIV_2 = 0x00, /*!< master clock frequency division 2 */ + SPI_MCLK_DIV_3 = 0x0A, /*!< master clock frequency division 3 */ + SPI_MCLK_DIV_4 = 0x01, /*!< master clock frequency division 4 */ + SPI_MCLK_DIV_8 = 0x02, /*!< master clock frequency division 8 */ + SPI_MCLK_DIV_16 = 0x03, /*!< master clock frequency division 16 */ + SPI_MCLK_DIV_32 = 0x04, /*!< master clock frequency division 32 */ + SPI_MCLK_DIV_64 = 0x05, /*!< master clock frequency division 64 */ + SPI_MCLK_DIV_128 = 0x06, /*!< master clock frequency division 128 */ + SPI_MCLK_DIV_256 = 0x07, /*!< master clock frequency division 256 */ + SPI_MCLK_DIV_512 = 0x08, /*!< master clock frequency division 512 */ + SPI_MCLK_DIV_1024 = 0x09 /*!< master clock frequency division 1024 */ +} spi_mclk_freq_div_type; + +/** + * @brief spi transmit first bit (lsb/msb) type + */ +typedef enum +{ + SPI_FIRST_BIT_MSB = 0x00, /*!< the frame format is msb first */ + SPI_FIRST_BIT_LSB = 0x01 /*!< the frame format is lsb first */ +} spi_first_bit_type; + +/** + * @brief spi transmission mode type + */ +typedef enum +{ + SPI_TRANSMIT_FULL_DUPLEX = 0x00, /*!< dual line unidirectional full-duplex mode(slben = 0 and ora = 0) */ + SPI_TRANSMIT_SIMPLEX_RX = 0x01, /*!< dual line unidirectional simplex receive-only mode(slben = 0 and ora = 1) */ + SPI_TRANSMIT_HALF_DUPLEX_RX = 0x02, /*!< single line bidirectional half duplex mode-receiving(slben = 1 and slbtd = 0) */ + SPI_TRANSMIT_HALF_DUPLEX_TX = 0x03 /*!< single line bidirectional half duplex mode-transmitting(slben = 1 and slbtd = 1) */ +} spi_transmission_mode_type; + +/** + * @brief spi crc direction type + */ +typedef enum +{ + SPI_CRC_RX = 0x0014, /*!< crc direction is rx */ + SPI_CRC_TX = 0x0018 /*!< crc direction is tx */ +} spi_crc_direction_type; + +/** + * @brief spi single line bidirectional direction type + */ +typedef enum +{ + SPI_HALF_DUPLEX_DIRECTION_RX = 0x00, /*!< single line bidirectional half duplex mode direction: receive(slbtd = 0) */ + SPI_HALF_DUPLEX_DIRECTION_TX = 0x01 /*!< single line bidirectional half duplex mode direction: transmit(slbtd = 1) */ +} spi_half_duplex_direction_type; + +/** + * @brief spi software cs internal level type + */ +typedef enum +{ + SPI_SWCS_INTERNAL_LEVEL_LOW = 0x00, /*!< internal level low */ + SPI_SWCS_INTERNAL_LEVEL_HIGHT = 0x01 /*!< internal level high */ +} spi_software_cs_level_type; + +/** + * @brief i2s audio protocol type + */ +typedef enum +{ + I2S_AUDIO_PROTOCOL_PHILLIPS = 0x00, /*!< i2s philip standard */ + I2S_AUDIO_PROTOCOL_MSB = 0x01, /*!< msb-justified standard */ + I2S_AUDIO_PROTOCOL_LSB = 0x02, /*!< lsb-justified standard */ + I2S_AUDIO_PROTOCOL_PCM_SHORT = 0x03, /*!< pcm standard-short frame */ + I2S_AUDIO_PROTOCOL_PCM_LONG = 0x04 /*!< pcm standard-long frame */ +} i2s_audio_protocol_type; + +/** + * @brief i2s audio frequency type + */ +typedef enum +{ + I2S_AUDIO_FREQUENCY_DEFAULT = 2, /*!< i2s audio sampling frequency default */ + I2S_AUDIO_FREQUENCY_8K = 8000, /*!< i2s audio sampling frequency 8k */ + I2S_AUDIO_FREQUENCY_11_025K = 11025, /*!< i2s audio sampling frequency 11.025k */ + I2S_AUDIO_FREQUENCY_16K = 16000, /*!< i2s audio sampling frequency 16k */ + I2S_AUDIO_FREQUENCY_22_05K = 22050, /*!< i2s audio sampling frequency 22.05k */ + I2S_AUDIO_FREQUENCY_32K = 32000, /*!< i2s audio sampling frequency 32k */ + I2S_AUDIO_FREQUENCY_44_1K = 44100, /*!< i2s audio sampling frequency 44.1k */ + I2S_AUDIO_FREQUENCY_48K = 48000, /*!< i2s audio sampling frequency 48k */ + I2S_AUDIO_FREQUENCY_96K = 96000, /*!< i2s audio sampling frequency 96k */ + I2S_AUDIO_FREQUENCY_192K = 192000 /*!< i2s audio sampling frequency 192k */ +} i2s_audio_sampling_freq_type; + +/** + * @brief i2s data bit num and channel bit num type + */ +typedef enum +{ + I2S_DATA_16BIT_CHANNEL_16BIT = 0x01, /*!< 16-bit data packed in 16-bit channel frame */ + I2S_DATA_16BIT_CHANNEL_32BIT = 0x02, /*!< 16-bit data packed in 32-bit channel frame */ + I2S_DATA_24BIT_CHANNEL_32BIT = 0x03, /*!< 24-bit data packed in 32-bit channel frame */ + I2S_DATA_32BIT_CHANNEL_32BIT = 0x04 /*!< 32-bit data packed in 32-bit channel frame */ +} i2s_data_channel_format_type; + +/** + * @brief i2s operation mode type + */ +typedef enum +{ + I2S_MODE_SLAVE_TX = 0x00, /*!< slave transmission mode */ + I2S_MODE_SLAVE_RX = 0x01, /*!< slave reception mode */ + I2S_MODE_MASTER_TX = 0x02, /*!< master transmission mode */ + I2S_MODE_MASTER_RX = 0x03 /*!< master reception mode */ +} i2s_operation_mode_type; + +/** + * @brief i2s clock polarity type + */ +typedef enum +{ + I2S_CLOCK_POLARITY_LOW = 0x00, /*!< i2s clock steady state is low level */ + I2S_CLOCK_POLARITY_HIGH = 0x01 /*!< i2s clock steady state is high level */ +} i2s_clock_polarity_type; + +/** + * @brief spi init type + */ +typedef struct +{ + spi_transmission_mode_type transmission_mode; /*!< transmission mode selection */ + spi_master_slave_mode_type master_slave_mode; /*!< master or slave mode selection */ + spi_mclk_freq_div_type mclk_freq_division; /*!< master clock frequency division selection */ + spi_first_bit_type first_bit_transmission;/*!< transmit lsb or msb selection */ + spi_frame_bit_num_type frame_bit_num; /*!< frame bit num 8 or 16 bit selection */ + spi_clock_polarity_type clock_polarity; /*!< clock polarity selection */ + spi_clock_phase_type clock_phase; /*!< clock phase selection */ + spi_cs_mode_type cs_mode_selection; /*!< hardware or software cs mode selection */ +} spi_init_type; + +/** + * @brief i2s init type + */ +typedef struct +{ + i2s_operation_mode_type operation_mode; /*!< operation mode selection */ + i2s_audio_protocol_type audio_protocol; /*!< audio protocol selection */ + i2s_audio_sampling_freq_type audio_sampling_freq; /*!< audio frequency selection */ + i2s_data_channel_format_type data_channel_format; /*!< data bit num and channel bit num selection */ + i2s_clock_polarity_type clock_polarity; /*!< clock polarity selection */ + confirm_state mclk_output_enable; /*!< mclk_output selection */ +} i2s_init_type; + +/** + * @brief type define spi register all + */ +typedef struct +{ + + /** + * @brief spi ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t clkpha : 1; /* [0] */ + __IO uint32_t clkpol : 1; /* [1] */ + __IO uint32_t msten : 1; /* [2] */ + __IO uint32_t mdiv_l : 3; /* [5:3] */ + __IO uint32_t spien : 1; /* [6] */ + __IO uint32_t ltf : 1; /* [7] */ + __IO uint32_t swcsil : 1; /* [8] */ + __IO uint32_t swcsen : 1; /* [9] */ + __IO uint32_t ora : 1; /* [10] */ + __IO uint32_t fbn : 1; /* [11] */ + __IO uint32_t ntc : 1; /* [12] */ + __IO uint32_t ccen : 1; /* [13] */ + __IO uint32_t slbtd : 1; /* [14] */ + __IO uint32_t slben : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } ctrl1_bit; + }; + + /** + * @brief spi ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t dmaren : 1; /* [0] */ + __IO uint32_t dmaten : 1; /* [1] */ + __IO uint32_t hwcsoe : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t tien : 1; /* [4] */ + __IO uint32_t errie : 1; /* [5] */ + __IO uint32_t rdbfie : 1; /* [6] */ + __IO uint32_t tdbeie : 1; /* [7] */ + __IO uint32_t mdiv_h : 1; /* [8] */ + __IO uint32_t mdiv3en : 1; /* [9] */ + __IO uint32_t reserved2 : 22;/* [31:10] */ + } ctrl2_bit; + }; + + /** + * @brief spi sts register, offset:0x08 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t rdbf : 1; /* [0] */ + __IO uint32_t tdbe : 1; /* [1] */ + __IO uint32_t acs : 1; /* [2] */ + __IO uint32_t tuerr : 1; /* [3] */ + __IO uint32_t ccerr : 1; /* [4] */ + __IO uint32_t mmerr : 1; /* [5] */ + __IO uint32_t roerr : 1; /* [6] */ + __IO uint32_t bf : 1; /* [7] */ + __IO uint32_t cspas : 1; /* [8] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } sts_bit; + }; + + /** + * @brief spi dt register, offset:0x0C + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } dt_bit; + }; + + /** + * @brief spi cpoly register, offset:0x10 + */ + union + { + __IO uint32_t cpoly; + struct + { + __IO uint32_t cpoly : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cpoly_bit; + }; + + /** + * @brief spi rcrc register, offset:0x14 + */ + union + { + __IO uint32_t rcrc; + struct + { + __IO uint32_t rcrc : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } rcrc_bit; + }; + + /** + * @brief spi tcrc register, offset:0x18 + */ + union + { + __IO uint32_t tcrc; + struct + { + __IO uint32_t tcrc : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } tcrc_bit; + }; + + /** + * @brief spi i2sctrl register, offset:0x1C + */ + union + { + __IO uint32_t i2sctrl; + struct + { + __IO uint32_t i2scbn : 1; /* [0] */ + __IO uint32_t i2sdbn : 2; /* [2:1] */ + __IO uint32_t i2sclkpol : 1; /* [3] */ + __IO uint32_t stdsel : 2; /* [5:4] */ + __IO uint32_t reserved1 : 1; /* [6] */ + __IO uint32_t pcmfssel : 1; /* [7] */ + __IO uint32_t opersel : 2; /* [9:8] */ + __IO uint32_t i2sen : 1; /* [10] */ + __IO uint32_t i2smsel : 1; /* [11] */ + __IO uint32_t reserved2 : 20;/* [31:12] */ + } i2sctrl_bit; + }; + + /** + * @brief spi i2sclk register, offset:0x20 + */ + union + { + __IO uint32_t i2sclk; + struct + { + __IO uint32_t i2sdiv_l : 8; /* [7:0] */ + __IO uint32_t i2sodd : 1; /* [8] */ + __IO uint32_t i2smclkoe : 1; /* [9] */ + __IO uint32_t i2sdiv_h : 2; /* [11:10] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } i2sclk_bit; + }; + +} spi_type; + +/** + * @} + */ + +#define SPI1 ((spi_type *) SPI1_BASE) +#define SPI2 ((spi_type *) SPI2_BASE) +#define SPI3 ((spi_type *) SPI3_BASE) +#define SPI4 ((spi_type *) SPI4_BASE) +#define I2S2EXT ((spi_type *) I2S2EXT_BASE) +#define I2S3EXT ((spi_type *) I2S3EXT_BASE) + +/** @defgroup SPI_exported_functions + * @{ + */ + +void spi_i2s_reset(spi_type *spi_x); +void spi_default_para_init(spi_init_type* spi_init_struct); +void spi_init(spi_type* spi_x, spi_init_type* spi_init_struct); +void spi_ti_mode_enable(spi_type* spi_x, confirm_state new_state); +void spi_crc_next_transmit(spi_type* spi_x); +void spi_crc_polynomial_set(spi_type* spi_x, uint16_t crc_poly); +uint16_t spi_crc_polynomial_get(spi_type* spi_x); +void spi_crc_enable(spi_type* spi_x, confirm_state new_state); +uint16_t spi_crc_value_get(spi_type* spi_x, spi_crc_direction_type crc_direction); +void spi_hardware_cs_output_enable(spi_type* spi_x, confirm_state new_state); +void spi_software_cs_internal_level_set(spi_type* spi_x, spi_software_cs_level_type level); +void spi_frame_bit_num_set(spi_type* spi_x, spi_frame_bit_num_type bit_num); +void spi_half_duplex_direction_set(spi_type* spi_x, spi_half_duplex_direction_type direction); +void spi_enable(spi_type* spi_x, confirm_state new_state); +void i2s_default_para_init(i2s_init_type* i2s_init_struct); +void i2s_init(spi_type* spi_x, i2s_init_type* i2s_init_struct); +void i2s_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_interrupt_enable(spi_type* spi_x, uint32_t spi_i2s_int, confirm_state new_state); +void spi_i2s_dma_transmitter_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_dma_receiver_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_data_transmit(spi_type* spi_x, uint16_t tx_data); +uint16_t spi_i2s_data_receive(spi_type* spi_x); +flag_status spi_i2s_flag_get(spi_type* spi_x, uint32_t spi_i2s_flag); +void spi_i2s_flag_clear(spi_type* spi_x, uint32_t spi_i2s_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h new file mode 100644 index 0000000000..1e4256bb1e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h @@ -0,0 +1,1006 @@ +/** + ************************************************************************** + * @file at32f435_437_tmr.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 tmr header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_TMR_H +#define __AT32F435_437_TMR_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup TMR + * @{ + */ + +/** @defgroup TMR_flags_definition + * @brief tmr flag + * @{ + */ + +#define TMR_OVF_FLAG ((uint32_t)0x000001) /*!< tmr flag overflow */ +#define TMR_C1_FLAG ((uint32_t)0x000002) /*!< tmr flag channel 1 */ +#define TMR_C2_FLAG ((uint32_t)0x000004) /*!< tmr flag channel 2 */ +#define TMR_C3_FLAG ((uint32_t)0x000008) /*!< tmr flag channel 3 */ +#define TMR_C4_FLAG ((uint32_t)0x000010) /*!< tmr flag channel 4 */ +#define TMR_C5_FLAG ((uint32_t)0x010000) /*!< tmr flag channel 5 */ +#define TMR_HALL_FLAG ((uint32_t)0x000020) /*!< tmr flag hall */ +#define TMR_TRIGGER_FLAG ((uint32_t)0x000040) /*!< tmr flag trigger */ +#define TMR_BRK_FLAG ((uint32_t)0x000080) /*!< tmr flag brake */ +#define TMR_C1_RECAPTURE_FLAG ((uint32_t)0x000200) /*!< tmr flag channel 1 recapture */ +#define TMR_C2_RECAPTURE_FLAG ((uint32_t)0x000400) /*!< tmr flag channel 2 recapture */ +#define TMR_C3_RECAPTURE_FLAG ((uint32_t)0x000800) /*!< tmr flag channel 3 recapture */ +#define TMR_C4_RECAPTURE_FLAG ((uint32_t)0x001000) /*!< tmr flag channel 4 recapture */ + +/** + * @} + */ + +/** @defgroup TMR_interrupt_select_type_definition + * @brief tmr interrupt select type + * @{ + */ + +#define TMR_OVF_INT ((uint32_t)0x000001) /*!< tmr interrupt overflow */ +#define TMR_C1_INT ((uint32_t)0x000002) /*!< tmr interrupt channel 1 */ +#define TMR_C2_INT ((uint32_t)0x000004) /*!< tmr interrupt channel 2 */ +#define TMR_C3_INT ((uint32_t)0x000008) /*!< tmr interrupt channel 3 */ +#define TMR_C4_INT ((uint32_t)0x000010) /*!< tmr interrupt channel 4 */ +#define TMR_HALL_INT ((uint32_t)0x000020) /*!< tmr interrupt hall */ +#define TMR_TRIGGER_INT ((uint32_t)0x000040) /*!< tmr interrupt trigger */ +#define TMR_BRK_INT ((uint32_t)0x000080) /*!< tmr interrupt brake */ + +/** + * @} + */ + +/** @defgroup TMR_exported_types + * @{ + */ + +/** + * @brief tmr clock division type + */ +typedef enum +{ + TMR_CLOCK_DIV1 = 0x00, /*!< tmr clock division 1 */ + TMR_CLOCK_DIV2 = 0x01, /*!< tmr clock division 2 */ + TMR_CLOCK_DIV4 = 0x02 /*!< tmr clock division 4 */ +} tmr_clock_division_type; + +/** + * @brief tmr counter mode type + */ +typedef enum +{ + TMR_COUNT_UP = 0x00, /*!< tmr counter mode up */ + TMR_COUNT_DOWN = 0x01, /*!< tmr counter mode down */ + TMR_COUNT_TWO_WAY_1 = 0x02, /*!< tmr counter mode two way 1 */ + TMR_COUNT_TWO_WAY_2 = 0x04, /*!< tmr counter mode two way 2 */ + TMR_COUNT_TWO_WAY_3 = 0x06 /*!< tmr counter mode two way 3 */ +} tmr_count_mode_type; + +/** + * @brief tmr primary mode select type + */ +typedef enum +{ + TMR_PRIMARY_SEL_RESET = 0x00, /*!< tmr primary mode select reset */ + TMR_PRIMARY_SEL_ENABLE = 0x01, /*!< tmr primary mode select enable */ + TMR_PRIMARY_SEL_OVERFLOW = 0x02, /*!< tmr primary mode select overflow */ + TMR_PRIMARY_SEL_COMPARE = 0x03, /*!< tmr primary mode select compare */ + TMR_PRIMARY_SEL_C1ORAW = 0x04, /*!< tmr primary mode select c1oraw */ + TMR_PRIMARY_SEL_C2ORAW = 0x05, /*!< tmr primary mode select c2oraw */ + TMR_PRIMARY_SEL_C3ORAW = 0x06, /*!< tmr primary mode select c3oraw */ + TMR_PRIMARY_SEL_C4ORAW = 0x07 /*!< tmr primary mode select c4oraw */ +} tmr_primary_select_type; + +/** + * @brief tmr subordinate mode input select type + */ +typedef enum +{ + TMR_SUB_INPUT_SEL_IS0 = 0x00, /*!< subordinate mode input select is0 */ + TMR_SUB_INPUT_SEL_IS1 = 0x01, /*!< subordinate mode input select is1 */ + TMR_SUB_INPUT_SEL_IS2 = 0x02, /*!< subordinate mode input select is2 */ + TMR_SUB_INPUT_SEL_IS3 = 0x03, /*!< subordinate mode input select is3 */ + TMR_SUB_INPUT_SEL_C1INC = 0x04, /*!< subordinate mode input select c1inc */ + TMR_SUB_INPUT_SEL_C1DF1 = 0x05, /*!< subordinate mode input select c1df1 */ + TMR_SUB_INPUT_SEL_C2DF2 = 0x06, /*!< subordinate mode input select c2df2 */ + TMR_SUB_INPUT_SEL_EXTIN = 0x07 /*!< subordinate mode input select extin */ +} sub_tmr_input_sel_type; + +/** + * @brief tmr subordinate mode select type + */ +typedef enum +{ + TMR_SUB_MODE_DIABLE = 0x00, /*!< subordinate mode disable */ + TMR_SUB_ENCODER_MODE_A = 0x01, /*!< subordinate mode select encoder mode a */ + TMR_SUB_ENCODER_MODE_B = 0x02, /*!< subordinate mode select encoder mode b */ + TMR_SUB_ENCODER_MODE_C = 0x03, /*!< subordinate mode select encoder mode c */ + TMR_SUB_RESET_MODE = 0x04, /*!< subordinate mode select reset */ + TMR_SUB_HANG_MODE = 0x05, /*!< subordinate mode select hang */ + TMR_SUB_TRIGGER_MODE = 0x06, /*!< subordinate mode select trigger */ + TMR_SUB_EXTERNAL_CLOCK_MODE_A = 0x07 /*!< subordinate mode external clock mode a */ +} tmr_sub_mode_select_type; + +/** + * @brief tmr encoder mode type + */ +typedef enum +{ + TMR_ENCODER_MODE_A = TMR_SUB_ENCODER_MODE_A, /*!< tmr encoder mode a */ + TMR_ENCODER_MODE_B = TMR_SUB_ENCODER_MODE_B, /*!< tmr encoder mode b */ + TMR_ENCODER_MODE_C = TMR_SUB_ENCODER_MODE_C /*!< tmr encoder mode c */ +} tmr_encoder_mode_type; + +/** + * @brief tmr output control mode type + */ +typedef enum +{ + TMR_OUTPUT_CONTROL_OFF = 0x00, /*!< tmr output control mode off */ + TMR_OUTPUT_CONTROL_HIGH = 0x01, /*!< tmr output control mode high */ + TMR_OUTPUT_CONTROL_LOW = 0x02, /*!< tmr output control mode low */ + TMR_OUTPUT_CONTROL_SWITCH = 0x03, /*!< tmr output control mode switch */ + TMR_OUTPUT_CONTROL_FORCE_LOW = 0x04, /*!< tmr output control mode force low */ + TMR_OUTPUT_CONTROL_FORCE_HIGH = 0x05, /*!< tmr output control mode force high */ + TMR_OUTPUT_CONTROL_PWM_MODE_A = 0x06, /*!< tmr output control mode pwm a */ + TMR_OUTPUT_CONTROL_PWM_MODE_B = 0x07 /*!< tmr output control mode pwm b */ +} tmr_output_control_mode_type; + +/** + * @brief tmr force output type + */ +typedef enum +{ + TMR_FORCE_OUTPUT_HIGH = TMR_OUTPUT_CONTROL_FORCE_HIGH, /*!< tmr force output high */ + TMR_FORCE_OUTPUT_LOW = TMR_OUTPUT_CONTROL_FORCE_LOW /*!< tmr force output low */ +} tmr_force_output_type; + +/** + * @brief tmr output channel polarity type + */ +typedef enum +{ + TMR_OUTPUT_ACTIVE_HIGH = 0x00, /*!< tmr output channel polarity high */ + TMR_OUTPUT_ACTIVE_LOW = 0x01 /*!< tmr output channel polarity low */ +} tmr_output_polarity_type; + +/** + * @brief tmr input channel polarity type + */ +typedef enum +{ + TMR_INPUT_RISING_EDGE = 0x00, /*!< tmr input channel polarity rising */ + TMR_INPUT_FALLING_EDGE = 0x01, /*!< tmr input channel polarity falling */ + TMR_INPUT_BOTH_EDGE = 0x03 /*!< tmr input channel polarity both edge */ +} tmr_input_polarity_type; + +/** + * @brief tmr channel select type + */ +typedef enum +{ + TMR_SELECT_CHANNEL_1 = 0x00, /*!< tmr channel select channel 1 */ + TMR_SELECT_CHANNEL_1C = 0x01, /*!< tmr channel select channel 1 complementary */ + TMR_SELECT_CHANNEL_2 = 0x02, /*!< tmr channel select channel 2 */ + TMR_SELECT_CHANNEL_2C = 0x03, /*!< tmr channel select channel 2 complementary */ + TMR_SELECT_CHANNEL_3 = 0x04, /*!< tmr channel select channel 3 */ + TMR_SELECT_CHANNEL_3C = 0x05, /*!< tmr channel select channel 3 complementary */ + TMR_SELECT_CHANNEL_4 = 0x06, /*!< tmr channel select channel 4 */ + TMR_SELECT_CHANNEL_5 = 0x07 /*!< tmr channel select channel 5 */ +} tmr_channel_select_type; + +/** + * @brief tmr channel1 input connected type + */ +typedef enum +{ + TMR_CHANEL1_CONNECTED_C1IRAW = 0x00, /*!< channel1 pins is only connected to C1IRAW input */ + TMR_CHANEL1_2_3_CONNECTED_C1IRAW_XOR = 0x01 /*!< channel1/2/3 pins are connected to C1IRAW input after xored */ +} tmr_channel1_input_connected_type; + +/** + * @brief tmr input channel mapped type channel direction + */ +typedef enum +{ + TMR_CC_CHANNEL_MAPPED_DIRECT = 0x01, /*!< channel is configured as input, mapped direct */ + TMR_CC_CHANNEL_MAPPED_INDIRECT = 0x02, /*!< channel is configured as input, mapped indirect */ + TMR_CC_CHANNEL_MAPPED_STI = 0x03 /*!< channel is configured as input, mapped trc */ +} tmr_input_direction_mapped_type; + +/** + * @brief tmr input divider type + */ +typedef enum +{ + TMR_CHANNEL_INPUT_DIV_1 = 0x00, /*!< tmr channel input divider 1 */ + TMR_CHANNEL_INPUT_DIV_2 = 0x01, /*!< tmr channel input divider 2 */ + TMR_CHANNEL_INPUT_DIV_4 = 0x02, /*!< tmr channel input divider 4 */ + TMR_CHANNEL_INPUT_DIV_8 = 0x03 /*!< tmr channel input divider 8 */ +} tmr_channel_input_divider_type; + +/** + * @brief tmr dma request source select type + */ +typedef enum +{ + TMR_DMA_REQUEST_BY_CHANNEL = 0x00, /*!< tmr dma request source select channel */ + TMR_DMA_REQUEST_BY_OVERFLOW = 0x01 /*!< tmr dma request source select overflow */ +} tmr_dma_request_source_type; + +/** + * @brief tmr dma request type + */ +typedef enum +{ + TMR_OVERFLOW_DMA_REQUEST = 0x00000100, /*!< tmr dma request select overflow */ + TMR_C1_DMA_REQUEST = 0x00000200, /*!< tmr dma request select channel 1 */ + TMR_C2_DMA_REQUEST = 0x00000400, /*!< tmr dma request select channel 2 */ + TMR_C3_DMA_REQUEST = 0x00000800, /*!< tmr dma request select channel 3 */ + TMR_C4_DMA_REQUEST = 0x00001000, /*!< tmr dma request select channel 4 */ + TMR_HALL_DMA_REQUEST = 0x00002000, /*!< tmr dma request select hall */ + TMR_TRIGGER_DMA_REQUEST = 0x00004000 /*!< tmr dma request select trigger */ +} tmr_dma_request_type; + +/** + * @brief tmr event triggered by software type + */ +typedef enum +{ + TMR_OVERFLOW_SWTRIG = 0x00000001, /*!< tmr event triggered by software of overflow */ + TMR_C1_SWTRIG = 0x00000002, /*!< tmr event triggered by software of channel 1 */ + TMR_C2_SWTRIG = 0x00000004, /*!< tmr event triggered by software of channel 2 */ + TMR_C3_SWTRIG = 0x00000008, /*!< tmr event triggered by software of channel 3 */ + TMR_C4_SWTRIG = 0x00000010, /*!< tmr event triggered by software of channel 4 */ + TMR_HALL_SWTRIG = 0x00000020, /*!< tmr event triggered by software of hall */ + TMR_TRIGGER_SWTRIG = 0x00000040, /*!< tmr event triggered by software of trigger */ + TMR_BRK_SWTRIG = 0x00000080 /*!< tmr event triggered by software of brake */ +}tmr_event_trigger_type; + +/** + * @brief tmr polarity active type + */ +typedef enum +{ + TMR_POLARITY_ACTIVE_HIGH = 0x00, /*!< tmr polarity active high */ + TMR_POLARITY_ACTIVE_LOW = 0x01, /*!< tmr polarity active low */ + TMR_POLARITY_ACTIVE_BOTH = 0x02 /*!< tmr polarity active both high ande low */ +}tmr_polarity_active_type; + +/** + * @brief tmr external signal divider type + */ +typedef enum +{ + TMR_ES_FREQUENCY_DIV_1 = 0x00, /*!< tmr external signal frequency divider 1 */ + TMR_ES_FREQUENCY_DIV_2 = 0x01, /*!< tmr external signal frequency divider 2 */ + TMR_ES_FREQUENCY_DIV_4 = 0x02, /*!< tmr external signal frequency divider 4 */ + TMR_ES_FREQUENCY_DIV_8 = 0x03 /*!< tmr external signal frequency divider 8 */ +}tmr_external_signal_divider_type; + +/** + * @brief tmr external signal polarity type + */ +typedef enum +{ + TMR_ES_POLARITY_NON_INVERTED = 0x00, /*!< tmr external signal polarity non-inerted */ + TMR_ES_POLARITY_INVERTED = 0x01 /*!< tmr external signal polarity inerted */ +}tmr_external_signal_polarity_type; + +/** + * @brief tmr dma transfer length type + */ +typedef enum +{ + TMR_DMA_TRANSFER_1BYTE = 0x00, /*!< tmr dma transfer length 1 byte */ + TMR_DMA_TRANSFER_2BYTES = 0x01, /*!< tmr dma transfer length 2 bytes */ + TMR_DMA_TRANSFER_3BYTES = 0x02, /*!< tmr dma transfer length 3 bytes */ + TMR_DMA_TRANSFER_4BYTES = 0x03, /*!< tmr dma transfer length 4 bytes */ + TMR_DMA_TRANSFER_5BYTES = 0x04, /*!< tmr dma transfer length 5 bytes */ + TMR_DMA_TRANSFER_6BYTES = 0x05, /*!< tmr dma transfer length 6 bytes */ + TMR_DMA_TRANSFER_7BYTES = 0x06, /*!< tmr dma transfer length 7 bytes */ + TMR_DMA_TRANSFER_8BYTES = 0x07, /*!< tmr dma transfer length 8 bytes */ + TMR_DMA_TRANSFER_9BYTES = 0x08, /*!< tmr dma transfer length 9 bytes */ + TMR_DMA_TRANSFER_10BYTES = 0x09, /*!< tmr dma transfer length 10 bytes */ + TMR_DMA_TRANSFER_11BYTES = 0x0A, /*!< tmr dma transfer length 11 bytes */ + TMR_DMA_TRANSFER_12BYTES = 0x0B, /*!< tmr dma transfer length 12 bytes */ + TMR_DMA_TRANSFER_13BYTES = 0x0C, /*!< tmr dma transfer length 13 bytes */ + TMR_DMA_TRANSFER_14BYTES = 0x0D, /*!< tmr dma transfer length 14 bytes */ + TMR_DMA_TRANSFER_15BYTES = 0x0E, /*!< tmr dma transfer length 15 bytes */ + TMR_DMA_TRANSFER_16BYTES = 0x0F, /*!< tmr dma transfer length 16 bytes */ + TMR_DMA_TRANSFER_17BYTES = 0x10, /*!< tmr dma transfer length 17 bytes */ + TMR_DMA_TRANSFER_18BYTES = 0x11 /*!< tmr dma transfer length 18 bytes */ +}tmr_dma_transfer_length_type; + +/** + * @brief tmr dma base address type + */ +typedef enum +{ + TMR_CTRL1_ADDRESS = 0x0000, /*!< tmr dma base address ctrl1 */ + TMR_CTRL2_ADDRESS = 0x0001, /*!< tmr dma base address ctrl2 */ + TMR_STCTRL_ADDRESS = 0x0002, /*!< tmr dma base address stctrl */ + TMR_IDEN_ADDRESS = 0x0003, /*!< tmr dma base address iden */ + TMR_ISTS_ADDRESS = 0x0004, /*!< tmr dma base address ists */ + TMR_SWEVT_ADDRESS = 0x0005, /*!< tmr dma base address swevt */ + TMR_CM1_ADDRESS = 0x0006, /*!< tmr dma base address cm1 */ + TMR_CM2_ADDRESS = 0x0007, /*!< tmr dma base address cm2 */ + TMR_CCTRL_ADDRESS = 0x0008, /*!< tmr dma base address cctrl */ + TMR_CVAL_ADDRESS = 0x0009, /*!< tmr dma base address cval */ + TMR_DIV_ADDRESS = 0x000A, /*!< tmr dma base address div */ + TMR_PR_ADDRESS = 0x000B, /*!< tmr dma base address pr */ + TMR_RPR_ADDRESS = 0x000C, /*!< tmr dma base address rpr */ + TMR_C1DT_ADDRESS = 0x000D, /*!< tmr dma base address c1dt */ + TMR_C2DT_ADDRESS = 0x000E, /*!< tmr dma base address c2dt */ + TMR_C3DT_ADDRESS = 0x000F, /*!< tmr dma base address c3dt */ + TMR_C4DT_ADDRESS = 0x0010, /*!< tmr dma base address c4dt */ + TMR_BRK_ADDRESS = 0x0011, /*!< tmr dma base address brake */ + TMR_DMACTRL_ADDRESS = 0x0012 /*!< tmr dma base address dmactrl */ +}tmr_dma_address_type; + +/** + * @brief tmr brk polarity type + */ +typedef enum +{ + TMR_BRK_INPUT_ACTIVE_LOW = 0x00, /*!< tmr brk input channel active low */ + TMR_BRK_INPUT_ACTIVE_HIGH = 0x01 /*!< tmr brk input channel active high */ +}tmr_brk_polarity_type; + +/** + * @brief tmr write protect level type + */ +typedef enum +{ + TMR_WP_OFF = 0x00, /*!< tmr write protect off */ + TMR_WP_LEVEL_3 = 0x01, /*!< tmr write protect level 3 */ + TMR_WP_LEVEL_2 = 0x02, /*!< tmr write protect level 2 */ + TMR_WP_LEVEL_1 = 0x03 /*!< tmr write protect level 1 */ +}tmr_wp_level_type; + +/** + * @brief tmr input remap type + */ +typedef enum +{ + TMR2_TMR8TRGOUT_TMR5_GPIO = 0x00, /*!< tmr2 input remap to tmr8_trgout or tmr5 remap to gpio */ + TMR2_PTP_TMR5_LICK = 0x01, /*!< tmr2 input remap to ptp or tmr5 remap to lick */ + TMR2_OTG1FS_TMR5_LEXT = 0x02, /*!< tmr2 input remap to otg1fs or tmr5 remap to lext */ + TMR2_OTG2FS_TMR5_ERTC = 0x03 /*!< tmr2 input remap to otg2fs or tmr5 remap to ertc */ +}tmr_input_remap_type ; +/** + + * @brief tmr output config type + */ +typedef struct +{ + tmr_output_control_mode_type oc_mode; /*!< output channel mode */ + confirm_state oc_idle_state; /*!< output channel idle state */ + confirm_state occ_idle_state; /*!< output channel complementary idle state */ + tmr_output_polarity_type oc_polarity; /*!< output channel polarity */ + tmr_output_polarity_type occ_polarity; /*!< output channel complementary polarity */ + confirm_state oc_output_state; /*!< output channel enable */ + confirm_state occ_output_state; /*!< output channel complementary enable */ +} tmr_output_config_type; + +/** + * @brief tmr input capture config type + */ +typedef struct +{ + tmr_channel_select_type input_channel_select; /*!< tmr input channel select */ + tmr_input_polarity_type input_polarity_select; /*!< tmr input polarity select */ + tmr_input_direction_mapped_type input_mapped_select; /*!< tmr channel mapped direct or indirect */ + uint8_t input_filter_value; /*!< tmr channel filter value */ +} tmr_input_config_type; + +/** + * @brief tmr brkdt config type + */ +typedef struct +{ + uint8_t deadtime; /*!< dead-time generator setup */ + tmr_brk_polarity_type brk_polarity; /*!< tmr brake polarity */ + tmr_wp_level_type wp_level; /*!< write protect configuration */ + confirm_state auto_output_enable; /*!< automatic output enable */ + confirm_state fcsoen_state; /*!< frozen channel status when output enable */ + confirm_state fcsodis_state; /*!< frozen channel status when output disable */ + confirm_state brk_enable; /*!< tmr brk enale */ +} tmr_brkdt_config_type; + +/** + * @brief type define tmr register all + */ +typedef struct +{ + /** + * @brief tmr ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t tmren : 1; /* [0] */ + __IO uint32_t ovfen : 1; /* [1] */ + __IO uint32_t ovfs : 1; /* [2] */ + __IO uint32_t ocmen : 1; /* [3] */ + __IO uint32_t cnt_dir : 3; /* [6:4] */ + __IO uint32_t prben : 1; /* [7] */ + __IO uint32_t clkdiv : 2; /* [9:8] */ + __IO uint32_t pmen : 1; /* [10] */ + __IO uint32_t reserved1 : 21;/* [31:11] */ + } ctrl1_bit; + }; + + /** + * @brief tmr ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t cbctrl : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t ccfs : 1; /* [2] */ + __IO uint32_t drs : 1; /* [3] */ + __IO uint32_t ptos : 3; /* [6:4] */ + __IO uint32_t c1insel : 1; /* [7] */ + __IO uint32_t c1ios : 1; /* [8] */ + __IO uint32_t c1cios : 1; /* [9] */ + __IO uint32_t c2ios : 1; /* [10] */ + __IO uint32_t c2cios : 1; /* [11] */ + __IO uint32_t c3ios : 1; /* [12] */ + __IO uint32_t c3cios : 1; /* [13] */ + __IO uint32_t c4ios : 1; /* [14] */ + __IO uint32_t reserved2 : 16;/* [30:15] */ + __IO uint32_t trgout2en : 1; /* [31] */ + } ctrl2_bit; + }; + + /** + * @brief tmr smc register, offset:0x08 + */ + union + { + __IO uint32_t stctrl; + struct + { + __IO uint32_t smsel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t stis : 3; /* [6:4] */ + __IO uint32_t sts : 1; /* [7] */ + __IO uint32_t esf : 4; /* [11:8] */ + __IO uint32_t esdiv : 2; /* [13:12] */ + __IO uint32_t ecmben : 1; /* [14] */ + __IO uint32_t esp : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } stctrl_bit; + }; + + /** + * @brief tmr die register, offset:0x0C + */ + union + { + __IO uint32_t iden; + struct + { + __IO uint32_t ovfien : 1; /* [0] */ + __IO uint32_t c1ien : 1; /* [1] */ + __IO uint32_t c2ien : 1; /* [2] */ + __IO uint32_t c3ien : 1; /* [3] */ + __IO uint32_t c4ien : 1; /* [4] */ + __IO uint32_t hallien : 1; /* [5] */ + __IO uint32_t tien : 1; /* [6] */ + __IO uint32_t brkie : 1; /* [7] */ + __IO uint32_t ovfden : 1; /* [8] */ + __IO uint32_t c1den : 1; /* [9] */ + __IO uint32_t c2den : 1; /* [10] */ + __IO uint32_t c3den : 1; /* [11] */ + __IO uint32_t c4den : 1; /* [12] */ + __IO uint32_t hallde : 1; /* [13] */ + __IO uint32_t tden : 1; /* [14] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } iden_bit; + }; + + /** + * @brief tmr ists register, offset:0x10 + */ + union + { + __IO uint32_t ists; + struct + { + __IO uint32_t ovfif : 1; /* [0] */ + __IO uint32_t c1if : 1; /* [1] */ + __IO uint32_t c2if : 1; /* [2] */ + __IO uint32_t c3if : 1; /* [3] */ + __IO uint32_t c4if : 1; /* [4] */ + __IO uint32_t hallif : 1; /* [5] */ + __IO uint32_t trgif : 1; /* [6] */ + __IO uint32_t brkif : 1; /* [7] */ + __IO uint32_t reserved1 : 1; /* [8] */ + __IO uint32_t c1rf : 1; /* [9] */ + __IO uint32_t c2rf : 1; /* [10] */ + __IO uint32_t c3rf : 1; /* [11] */ + __IO uint32_t c4rf : 1; /* [12] */ + __IO uint32_t reserved2 : 19;/* [31:13] */ + } ists_bit; + }; + + /** + * @brief tmr eveg register, offset:0x14 + */ + union + { + __IO uint32_t swevt; + struct + { + __IO uint32_t ovfswtr : 1; /* [0] */ + __IO uint32_t c1swtr : 1; /* [1] */ + __IO uint32_t c2swtr : 1; /* [2] */ + __IO uint32_t c3swtr : 1; /* [3] */ + __IO uint32_t c4swtr : 1; /* [4] */ + __IO uint32_t hallswtr : 1; /* [5] */ + __IO uint32_t trgswtr : 1; /* [6] */ + __IO uint32_t brkswtr : 1; /* [7] */ + __IO uint32_t reserved : 24;/* [31:8] */ + } swevt_bit; + }; + + /** + * @brief tmr ccm1 register, offset:0x18 + */ + union + { + __IO uint32_t cm1; + + /** + * @brief channel mode + */ + struct + { + __IO uint32_t c1c : 2; /* [1:0] */ + __IO uint32_t c1oien : 1; /* [2] */ + __IO uint32_t c1oben : 1; /* [3] */ + __IO uint32_t c1octrl : 3; /* [6:4] */ + __IO uint32_t c1osen : 1; /* [7] */ + __IO uint32_t c2c : 2; /* [9:8] */ + __IO uint32_t c2oien : 1; /* [10] */ + __IO uint32_t c2oben : 1; /* [11] */ + __IO uint32_t c2octrl : 3; /* [14:12] */ + __IO uint32_t c2osen : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm1_output_bit; + + /** + * @brief input capture mode + */ + struct + { + __IO uint32_t c1c : 2; /* [1:0] */ + __IO uint32_t c1idiv : 2; /* [3:2] */ + __IO uint32_t c1df : 4; /* [7:4] */ + __IO uint32_t c2c : 2; /* [9:8] */ + __IO uint32_t c2idiv : 2; /* [11:10] */ + __IO uint32_t c2df : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm1_input_bit; + }; + + /** + * @brief tmr ccm2 register, offset:0x1C + */ + union + { + __IO uint32_t cm2; + + /** + * @brief channel mode + */ + struct + { + __IO uint32_t c3c : 2; /* [1:0] */ + __IO uint32_t c3oien : 1; /* [2] */ + __IO uint32_t c3oben : 1; /* [3] */ + __IO uint32_t c3octrl : 3; /* [6:4] */ + __IO uint32_t c3osen : 1; /* [7] */ + __IO uint32_t c4c : 2; /* [9:8] */ + __IO uint32_t c4oien : 1; /* [10] */ + __IO uint32_t c4oben : 1; /* [11] */ + __IO uint32_t c4octrl : 3; /* [14:12] */ + __IO uint32_t c4osen : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm2_output_bit; + + /** + * @brief input capture mode + */ + struct + { + __IO uint32_t c3c : 2; /* [1:0] */ + __IO uint32_t c3idiv : 2; /* [3:2] */ + __IO uint32_t c3df : 4; /* [7:4] */ + __IO uint32_t c4c : 2; /* [9:8] */ + __IO uint32_t c4idiv : 2; /* [11:10] */ + __IO uint32_t c4df : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm2_input_bit; + }; + + /** + * @brief tmr cce register, offset:0x20 + */ + union + { + uint32_t cctrl; + struct + { + __IO uint32_t c1en : 1; /* [0] */ + __IO uint32_t c1p : 1; /* [1] */ + __IO uint32_t c1cen : 1; /* [2] */ + __IO uint32_t c1cp : 1; /* [3] */ + __IO uint32_t c2en : 1; /* [4] */ + __IO uint32_t c2p : 1; /* [5] */ + __IO uint32_t c2cen : 1; /* [6] */ + __IO uint32_t c2cp : 1; /* [7] */ + __IO uint32_t c3en : 1; /* [8] */ + __IO uint32_t c3p : 1; /* [9] */ + __IO uint32_t c3cen : 1; /* [10] */ + __IO uint32_t c3cp : 1; /* [11] */ + __IO uint32_t c4en : 1; /* [12] */ + __IO uint32_t c4p : 1; /* [13] */ + __IO uint32_t reserved1 : 18;/* [31:14] */ + } cctrl_bit; + }; + + /** + * @brief tmr cnt register, offset:0x24 + */ + union + { + __IO uint32_t cval; + struct + { + __IO uint32_t cval : 32;/* [31:0] */ + } cval_bit; + }; + + /** + * @brief tmr div, offset:0x28 + */ + union + { + __IO uint32_t div; + struct + { + __IO uint32_t div : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } div_bit; + }; + + /** + * @brief tmr pr register, offset:0x2C + */ + union + { + __IO uint32_t pr; + struct + { + __IO uint32_t pr : 32;/* [31:0] */ + } pr_bit; + }; + + /** + * @brief tmr rpr register, offset:0x30 + */ + union + { + __IO uint32_t rpr; + struct + { + __IO uint32_t rpr : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } rpr_bit; + }; + + /** + * @brief tmr c1dt register, offset:0x34 + */ + union + { + uint32_t c1dt; + struct + { + __IO uint32_t c1dt : 32;/* [31:0] */ + } c1dt_bit; + }; + + /** + * @brief tmr c2dt register, offset:0x38 + */ + union + { + uint32_t c2dt; + struct + { + __IO uint32_t c2dt : 32;/* [31:0] */ + } c2dt_bit; + }; + + /** + * @brief tmr c3dt register, offset:0x3C + */ + union + { + __IO uint32_t c3dt; + struct + { + __IO uint32_t c3dt : 32;/* [31:0] */ + } c3dt_bit; + }; + + /** + * @brief tmr c4dt register, offset:0x40 + */ + union + { + __IO uint32_t c4dt; + struct + { + __IO uint32_t c4dt : 32;/* [31:0] */ + } c4dt_bit; + }; + + /** + * @brief tmr brk register, offset:0x44 + */ + union + { + __IO uint32_t brk; + struct + { + __IO uint32_t dtc : 8; /* [7:0] */ + __IO uint32_t wpc : 2; /* [9:8] */ + __IO uint32_t fcsodis : 1; /* [10] */ + __IO uint32_t fcsoen : 1; /* [11] */ + __IO uint32_t brken : 1; /* [12] */ + __IO uint32_t brkv : 1; /* [13] */ + __IO uint32_t aoen : 1; /* [14] */ + __IO uint32_t oen : 1; /* [15] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } brk_bit; + }; + /** + * @brief tmr dmactrl register, offset:0x48 + */ + union + { + __IO uint32_t dmactrl; + struct + { + __IO uint32_t addr : 5; /* [4:0] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t dtb : 5; /* [12:8] */ + __IO uint32_t reserved2 : 19;/* [31:13] */ + } dmactrl_bit; + }; + + /** + * @brief tmr dmadt register, offset:0x4C + */ + union + { + __IO uint32_t dmadt; + struct + { + __IO uint32_t dmadt : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } dmadt_bit; + }; + + /** + * @brief tmr rmp register, offset:0x50 + */ + union + { + __IO uint32_t rmp; + struct + { + __IO uint32_t reserved1 : 6; /* [5:0] */ + __IO uint32_t tmr5_ch4_irmp : 2; /* [7:6] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t tmr2_ch1_irmp : 2; /* [11:10] */ + __IO uint32_t reserved3 : 20;/* [31:16] */ + } rmp_bit; + }; + + /** + * @brief tmr reserved0 register, offset:0x54-0x6C + */ + __IO uint32_t reserved1[7]; + + /** + * @brief tmr cm3 register, offset:0x70 + */ + union + { + __IO uint32_t cm3; + struct + { + __IO uint32_t reserved1 : 2; /* [1:0] */ + __IO uint32_t c5oien : 1; /* [2] */ + __IO uint32_t c5oben : 1; /* [3] */ + __IO uint32_t c5octrl : 3; /* [6:4] */ + __IO uint32_t c5osen : 1; /* [7] */ + __IO uint32_t reserved2 : 24;/* [31:8] */ + } cm3_output_bit; + }; + + /** + * @brief tmr c5dt register, offset:0x74 + */ + union + { + __IO uint32_t c5dt; + struct + { + __IO uint32_t c5dt : 32;/* [31:0] */ + } c5dt_bit; + }; +} tmr_type; + +/** + * @} + */ + +#define TMR1 ((tmr_type *) TMR1_BASE) +#define TMR2 ((tmr_type *) TMR2_BASE) +#define TMR3 ((tmr_type *) TMR3_BASE) +#define TMR4 ((tmr_type *) TMR4_BASE) +#define TMR5 ((tmr_type *) TMR5_BASE) +#define TMR6 ((tmr_type *) TMR6_BASE) +#define TMR7 ((tmr_type *) TMR7_BASE) +#define TMR8 ((tmr_type *) TMR8_BASE) +#define TMR9 ((tmr_type *) TMR9_BASE) +#define TMR10 ((tmr_type *) TMR10_BASE) +#define TMR11 ((tmr_type *) TMR11_BASE) +#define TMR12 ((tmr_type *) TMR12_BASE) +#define TMR13 ((tmr_type *) TMR13_BASE) +#define TMR14 ((tmr_type *) TMR14_BASE) +#define TMR20 ((tmr_type *) TMR20_BASE) + +/** @defgroup TMR_exported_functions + * @{ + */ + +void tmr_reset(tmr_type *tmr_x); +void tmr_counter_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_output_default_para_init(tmr_output_config_type *tmr_output_struct); +void tmr_input_default_para_init(tmr_input_config_type *tmr_input_struct); +void tmr_brkdt_default_para_init(tmr_brkdt_config_type *tmr_brkdt_struct); +void tmr_base_init(tmr_type* tmr_x, uint32_t tmr_pr, uint32_t tmr_div); +void tmr_clock_source_div_set(tmr_type *tmr_x, tmr_clock_division_type tmr_clock_div); +void tmr_cnt_dir_set(tmr_type *tmr_x, tmr_count_mode_type tmr_cnt_dir); +void tmr_repetition_counter_set(tmr_type *tmr_x, uint8_t tmr_rpr_value); +void tmr_counter_value_set(tmr_type *tmr_x, uint32_t tmr_cnt_value); +uint32_t tmr_counter_value_get(tmr_type *tmr_x); +void tmr_div_value_set(tmr_type *tmr_x, uint32_t tmr_div_value); +uint32_t tmr_div_value_get(tmr_type *tmr_x); +void tmr_output_channel_config(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_config_type *tmr_output_struct); +void tmr_output_channel_mode_select(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_control_mode_type oc_mode); +void tmr_period_value_set(tmr_type *tmr_x, uint32_t tmr_pr_value); +uint32_t tmr_period_value_get(tmr_type *tmr_x); +void tmr_channel_value_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint32_t tmr_channel_value); +uint32_t tmr_channel_value_get(tmr_type *tmr_x, tmr_channel_select_type tmr_channel); +void tmr_period_buffer_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_output_channel_buffer_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_output_channel_immediately_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_output_channel_switch_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_one_cycle_mode_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_32_bit_function_enable (tmr_type *tmr_x, confirm_state new_state); +void tmr_overflow_request_source_set(tmr_type *tmr_x, confirm_state new_state); +void tmr_overflow_event_disable(tmr_type *tmr_x, confirm_state new_state); +void tmr_input_channel_init(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor); +void tmr_channel_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, confirm_state new_state); +void tmr_input_channel_filter_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint16_t filter_value); +void tmr_pwm_input_config(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor); +void tmr_channel1_input_select(tmr_type *tmr_x, tmr_channel1_input_connected_type ch1_connect); +void tmr_input_channel_divider_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_channel_input_divider_type divider_factor); +void tmr_primary_mode_select(tmr_type *tmr_x, tmr_primary_select_type primary_mode); +void tmr_sub_mode_select(tmr_type *tmr_x, tmr_sub_mode_select_type sub_mode); +void tmr_channel_dma_select(tmr_type *tmr_x, tmr_dma_request_source_type cc_dma_select); +void tmr_hall_select(tmr_type *tmr_x, confirm_state new_state); +void tmr_channel_buffer_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_trgout2_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_trigger_input_select(tmr_type *tmr_x, sub_tmr_input_sel_type trigger_select); +void tmr_sub_sync_mode_set(tmr_type *tmr_x, confirm_state new_state); +void tmr_dma_request_enable(tmr_type *tmr_x, tmr_dma_request_type dma_request, confirm_state new_state); +void tmr_interrupt_enable(tmr_type *tmr_x, uint32_t tmr_interrupt, confirm_state new_state); +flag_status tmr_flag_get(tmr_type *tmr_x, uint32_t tmr_flag); +void tmr_flag_clear(tmr_type *tmr_x, uint32_t tmr_flag); +void tmr_event_sw_trigger(tmr_type *tmr_x, tmr_event_trigger_type tmr_event); +void tmr_output_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_internal_clock_set(tmr_type *tmr_x); +void tmr_output_channel_polarity_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_polarity_active_type oc_polarity); +void tmr_external_clock_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_external_clock_mode1_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_external_clock_mode2_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_encoder_mode_config(tmr_type *tmr_x, tmr_encoder_mode_type encoder_mode, tmr_input_polarity_type \ + ic1_polarity, tmr_input_polarity_type ic2_polarity); +void tmr_force_output_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_force_output_type force_output); +void tmr_dma_control_config(tmr_type *tmr_x, tmr_dma_transfer_length_type dma_length, \ + tmr_dma_address_type dma_base_address); +void tmr_brkdt_config(tmr_type *tmr_x, tmr_brkdt_config_type *brkdt_struct); +void tmr_iremap_config(tmr_type *tmr_x, tmr_input_remap_type input_remap); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h new file mode 100644 index 0000000000..e7f2741815 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h @@ -0,0 +1,412 @@ +/** + ************************************************************************** + * @file at32f435_437_usart.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 usart header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_USART_H +#define __AT32F435_437_USART_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/** @defgroup USART_flags_definition + * @brief usart flag + * @{ + */ + +#define USART_PERR_FLAG ((uint32_t)0x00000001) /*!< usart parity error flag */ +#define USART_FERR_FLAG ((uint32_t)0x00000002) /*!< usart framing error flag */ +#define USART_NERR_FLAG ((uint32_t)0x00000004) /*!< usart noise error flag */ +#define USART_ROERR_FLAG ((uint32_t)0x00000008) /*!< usart receiver overflow error flag */ +#define USART_IDLEF_FLAG ((uint32_t)0x00000010) /*!< usart idle flag */ +#define USART_RDBF_FLAG ((uint32_t)0x00000020) /*!< usart receive data buffer full flag */ +#define USART_TDC_FLAG ((uint32_t)0x00000040) /*!< usart transmit data complete flag */ +#define USART_TDBE_FLAG ((uint32_t)0x00000080) /*!< usart transmit data buffer empty flag */ +#define USART_BFF_FLAG ((uint32_t)0x00000100) /*!< usart break frame flag */ +#define USART_CTSCF_FLAG ((uint32_t)0x00000200) /*!< usart cts change flag */ + +/** + * @} + */ + +/** @defgroup USART_interrupts_definition + * @brief usart interrupt + * @{ + */ + +#define USART_IDLE_INT MAKE_VALUE(0x0C,0x04) /*!< usart idle interrupt */ +#define USART_RDBF_INT MAKE_VALUE(0x0C,0x05) /*!< usart receive data buffer full interrupt */ +#define USART_TDC_INT MAKE_VALUE(0x0C,0x06) /*!< usart transmit data complete interrupt */ +#define USART_TDBE_INT MAKE_VALUE(0x0C,0x07) /*!< usart transmit data buffer empty interrupt */ +#define USART_PERR_INT MAKE_VALUE(0x0C,0x08) /*!< usart parity error interrupt */ +#define USART_BF_INT MAKE_VALUE(0x10,0x06) /*!< usart break frame interrupt */ +#define USART_ERR_INT MAKE_VALUE(0x14,0x00) /*!< usart error interrupt */ +#define USART_CTSCF_INT MAKE_VALUE(0x14,0x0A) /*!< usart cts change interrupt */ + +/** + * @} + */ + +/** @defgroup USART_exported_types + * @{ + */ + +/** + * @brief usart parity selection type + */ +typedef enum +{ + USART_PARITY_NONE = 0x00, /*!< usart no parity */ + USART_PARITY_EVEN = 0x01, /*!< usart even parity */ + USART_PARITY_ODD = 0x02 /*!< usart odd parity */ +} usart_parity_selection_type; + +/** + * @brief usart wakeup mode type + */ +typedef enum +{ + USART_WAKEUP_BY_IDLE_FRAME = 0x00, /*!< usart wakeup by idle frame */ + USART_WAKEUP_BY_MATCHING_ID = 0x01 /*!< usart wakeup by matching id */ +} usart_wakeup_mode_type; + +/** + * @brief usart data bit num type + */ +typedef enum +{ + USART_DATA_7BITS = 0x00, /*!< usart data size is 7 bits */ + USART_DATA_8BITS = 0x01, /*!< usart data size is 8 bits */ + USART_DATA_9BITS = 0x02 /*!< usart data size is 9 bits */ +} usart_data_bit_num_type; + +/** + * @brief usart break frame bit num type + */ +typedef enum +{ + USART_BREAK_10BITS = 0x00, /*!< usart lin mode berak frame detection 10 bits */ + USART_BREAK_11BITS = 0x01 /*!< usart lin mode berak frame detection 11 bits */ +} usart_break_bit_num_type; + +/** + * @brief usart phase of the clock type + */ +typedef enum +{ + USART_CLOCK_PHASE_1EDGE = 0x00, /*!< usart data capture is done on the clock leading edge */ + USART_CLOCK_PHASE_2EDGE = 0x01 /*!< usart data capture is done on the clock trailing edge */ +} usart_clock_phase_type; + +/** + * @brief usart polarity of the clock type + */ +typedef enum +{ + USART_CLOCK_POLARITY_LOW = 0x00, /*!< usart clock stay low level outside transmission window */ + USART_CLOCK_POLARITY_HIGH = 0x01 /*!< usart clock stay high level outside transmission window */ +} usart_clock_polarity_type; + +/** + * @brief usart last bit clock pulse type + */ +typedef enum +{ + USART_CLOCK_LAST_BIT_NONE = 0x00, /*!< usart clock pulse of the last data bit is not outputted */ + USART_CLOCK_LAST_BIT_OUTPUT = 0x01 /*!< usart clock pulse of the last data bit is outputted */ +} usart_lbcp_type; + +/** + * @brief usart stop bit num type + */ +typedef enum +{ + USART_STOP_1_BIT = 0x00, /*!< usart stop bits num is 1 */ + USART_STOP_0_5_BIT = 0x01, /*!< usart stop bits num is 0.5 */ + USART_STOP_2_BIT = 0x02, /*!< usart stop bits num is 2 */ + USART_STOP_1_5_BIT = 0x03 /*!< usart stop bits num is 1.5 */ +} usart_stop_bit_num_type; + +/** + * @brief usart hardware flow control type + */ +typedef enum +{ + USART_HARDWARE_FLOW_NONE = 0x00, /*!< usart without hardware flow */ + USART_HARDWARE_FLOW_RTS = 0x01, /*!< usart hardware flow only rts */ + USART_HARDWARE_FLOW_CTS = 0x02, /*!< usart hardware flow only cts */ + USART_HARDWARE_FLOW_RTS_CTS = 0x03 /*!< usart hardware flow both rts and cts */ +} usart_hardware_flow_control_type; + +/** + * @brief usart identification bit num type + */ +typedef enum +{ + USART_ID_FIXED_4_BIT = 0x00, /*!< usart id bit num fixed 4 bits */ + USART_ID_RELATED_DATA_BIT = 0x01 /*!< usart id bit num related data bits */ +} usart_identification_bit_num_type; + +/** + * @brief usart de polarity type + */ +typedef enum +{ + USART_DE_POLARITY_HIGH = 0x00, /*!< usart de polarity high */ + USART_DE_POLARITY_LOW = 0x01 /*!< usart de polarity low */ +} usart_de_polarity_type; + +/** + * @brief type define usart register all + */ +typedef struct +{ + /** + * @brief usart sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t perr : 1; /* [0] */ + __IO uint32_t ferr : 1; /* [1] */ + __IO uint32_t nerr : 1; /* [2] */ + __IO uint32_t roerr : 1; /* [3] */ + __IO uint32_t idlef : 1; /* [4] */ + __IO uint32_t rdbf : 1; /* [5] */ + __IO uint32_t tdc : 1; /* [6] */ + __IO uint32_t tdbe : 1; /* [7] */ + __IO uint32_t bff : 1; /* [8] */ + __IO uint32_t ctscf : 1; /* [9] */ + __IO uint32_t reserved1 : 22;/* [31:10] */ + } sts_bit; + }; + + /** + * @brief usart dt register, offset:0x04 + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 9; /* [8:0] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } dt_bit; + }; + + /** + * @brief usart baudr register, offset:0x08 + */ + union + { + __IO uint32_t baudr; + struct + { + __IO uint32_t div : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } baudr_bit; + }; + + /** + * @brief usart ctrl1 register, offset:0x0C + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t sbf : 1; /* [0] */ + __IO uint32_t rm : 1; /* [1] */ + __IO uint32_t ren : 1; /* [2] */ + __IO uint32_t ten : 1; /* [3] */ + __IO uint32_t idleien : 1; /* [4] */ + __IO uint32_t rdbfien : 1; /* [5] */ + __IO uint32_t tdcien : 1; /* [6] */ + __IO uint32_t tdbeien : 1; /* [7] */ + __IO uint32_t perrien : 1; /* [8] */ + __IO uint32_t psel : 1; /* [9] */ + __IO uint32_t pen : 1; /* [10] */ + __IO uint32_t wum : 1; /* [11] */ + __IO uint32_t dbn_l : 1; /* [12] */ + __IO uint32_t uen : 1; /* [13] */ + __IO uint32_t reserved1 : 2; /* [15:14] */ + __IO uint32_t tcdt : 5; /* [20:16] */ + __IO uint32_t tsdt : 5; /* [25:21] */ + __IO uint32_t reserved2 : 2; /* [27:26] */ + __IO uint32_t dbn_h : 1; /* [28] */ + __IO uint32_t reserved3 : 3; /* [31:29] */ + } ctrl1_bit; + }; + + /** + * @brief usart ctrl2 register, offset:0x10 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t id_l : 4; /* [3:0] */ + __IO uint32_t idbn : 1; /* [4] */ + __IO uint32_t bfbn : 1; /* [5] */ + __IO uint32_t bfien : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t lbcp : 1; /* [8] */ + __IO uint32_t clkpha : 1; /* [9] */ + __IO uint32_t clkpol : 1; /* [10] */ + __IO uint32_t clken : 1; /* [11] */ + __IO uint32_t stopbn : 2; /* [13:12] */ + __IO uint32_t linen : 1; /* [14] */ + __IO uint32_t trpswap : 1; /* [15] */ + __IO uint32_t reserved2 : 12;/* [27:16] */ + __IO uint32_t id_h : 4; /* [31:28] */ + } ctrl2_bit; + }; + + /** + * @brief usart ctrl3 register, offset:0x14 + */ + union + { + __IO uint32_t ctrl3; + struct + { + __IO uint32_t errien : 1; /* [0] */ + __IO uint32_t irdaen : 1; /* [1] */ + __IO uint32_t irdalp : 1; /* [2] */ + __IO uint32_t slben : 1; /* [3] */ + __IO uint32_t scnacken : 1; /* [4] */ + __IO uint32_t scmen : 1; /* [5] */ + __IO uint32_t dmaren : 1; /* [6] */ + __IO uint32_t dmaten : 1; /* [7] */ + __IO uint32_t rtsen : 1; /* [8] */ + __IO uint32_t ctsen : 1; /* [9] */ + __IO uint32_t ctscfien : 1; /* [10] */ + __IO uint32_t reserved1 : 3; /* [13:11] */ + __IO uint32_t rs485en : 1; /* [14] */ + __IO uint32_t dep : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } ctrl3_bit; + }; + + /** + * @brief usart gdiv register, offset:0x18 + */ + union + { + __IO uint32_t gdiv; + struct + { + __IO uint32_t isdiv : 8; /* [7:0] */ + __IO uint32_t scgt : 8; /* [15:8] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } gdiv_bit; + }; +} usart_type; + +/** + * @} + */ + +#define USART1 ((usart_type *) USART1_BASE) +#define USART2 ((usart_type *) USART2_BASE) +#define USART3 ((usart_type *) USART3_BASE) +#define UART4 ((usart_type *) UART4_BASE) +#define UART5 ((usart_type *) UART5_BASE) +#define USART6 ((usart_type *) USART6_BASE) +#define UART7 ((usart_type *) UART7_BASE) +#define UART8 ((usart_type *) UART8_BASE) + +/** @defgroup USART_exported_functions + * @{ + */ + +void usart_reset(usart_type* usart_x); +void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit); +void usart_parity_selection_config(usart_type* usart_x, usart_parity_selection_type parity); +void usart_enable(usart_type* usart_x, confirm_state new_state); +void usart_transmitter_enable(usart_type* usart_x, confirm_state new_state); +void usart_receiver_enable(usart_type* usart_x, confirm_state new_state); +void usart_clock_config(usart_type* usart_x, usart_clock_polarity_type clk_pol, usart_clock_phase_type clk_pha, usart_lbcp_type clk_lb); +void usart_clock_enable(usart_type* usart_x, confirm_state new_state); +void usart_interrupt_enable(usart_type* usart_x, uint32_t usart_int, confirm_state new_state); +void usart_dma_transmitter_enable(usart_type* usart_x, confirm_state new_state); +void usart_dma_receiver_enable(usart_type* usart_x, confirm_state new_state); +void usart_wakeup_id_set(usart_type* usart_x, uint8_t usart_id); +void usart_wakeup_mode_set(usart_type* usart_x, usart_wakeup_mode_type wakeup_mode); +void usart_receiver_mute_enable(usart_type* usart_x, confirm_state new_state); +void usart_break_bit_num_set(usart_type* usart_x, usart_break_bit_num_type break_bit); +void usart_lin_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_data_transmit(usart_type* usart_x, uint16_t data); +uint16_t usart_data_receive(usart_type* usart_x); +void usart_break_send(usart_type* usart_x); +void usart_smartcard_guard_time_set(usart_type* usart_x, uint8_t guard_time_val); +void usart_irda_smartcard_division_set(usart_type* usart_x, uint8_t div_val); +void usart_smartcard_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_smartcard_nack_set(usart_type* usart_x, confirm_state new_state); +void usart_single_line_halfduplex_select(usart_type* usart_x, confirm_state new_state); +void usart_irda_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_irda_low_power_enable(usart_type* usart_x, confirm_state new_state); +void usart_hardware_flow_control_set(usart_type* usart_x,usart_hardware_flow_control_type flow_state); +flag_status usart_flag_get(usart_type* usart_x, uint32_t flag); +void usart_flag_clear(usart_type* usart_x, uint32_t flag); +void usart_rs485_delay_time_config(usart_type* usart_x, uint8_t start_delay_time, uint8_t complete_delay_time); +void usart_transmit_receive_pin_swap(usart_type* usart_x, confirm_state new_state); +void usart_id_bit_num_set(usart_type* usart_x, usart_identification_bit_num_type id_bit_num); +void usart_de_polarity_set(usart_type* usart_x, usart_de_polarity_type de_polarity); +void usart_rs485_mode_enable(usart_type* usart_x, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h new file mode 100644 index 0000000000..c6ab3b6399 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h @@ -0,0 +1,1423 @@ +/** + ************************************************************************** + * @file at32f435_437_usb.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_USB_H +#define __AT32F435_437_USB_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup USB + * @{ + */ + +/** @defgroup USB_global_interrupts_definition + * @brief usb global interrupt mask + * @{ + */ + +#define USB_OTG_MODEMIS_INT ((uint32_t)0x00000002) /*!< usb otg mode mismatch interrupt */ +#define USB_OTG_OTGINT_INT ((uint32_t)0x00000004) /*!< usb otg interrupt */ +#define USB_OTG_SOF_INT ((uint32_t)0x00000008) /*!< usb otg sof interrupt */ +#define USB_OTG_RXFLVL_INT ((uint32_t)0x00000010) /*!< usb otg receive fifo non-empty interrupt */ +#define USB_OTG_NPTXFEMP_INT ((uint32_t)0x00000020) /*!< usb otg non-periodic tx fifo empty interrupt */ +#define USB_OTG_GINNAKEFF_INT ((uint32_t)0x00000040) /*!< usb otg global non-periodic in nak effective interrupt */ +#define USB_OTG_GOUTNAKEFF_INT ((uint32_t)0x00000080) /*!< usb otg global out nak effective interrupt */ +#define USB_OTG_ERLYSUSP_INT ((uint32_t)0x00000400) /*!< usb otg early suspend interrupt */ +#define USB_OTG_USBSUSP_INT ((uint32_t)0x00000800) /*!< usb otg suspend interrupt */ +#define USB_OTG_USBRST_INT ((uint32_t)0x00001000) /*!< usb otg reset interrupt */ +#define USB_OTG_ENUMDONE_INT ((uint32_t)0x00002000) /*!< usb otg enumeration done interrupt */ +#define USB_OTG_ISOOUTDROP_INT ((uint32_t)0x00004000) /*!< usb otg isochronous out packet dropped interrut */ +#define USB_OTG_EOPF_INT ((uint32_t)0x00008000) /*!< usb otg eop interrupt */ +#define USB_OTG_IEPT_INT ((uint32_t)0x00040000) /*!< usb otg in endpoint interrupt */ +#define USB_OTG_OEPT_INT ((uint32_t)0x00080000) /*!< usb otg out endpoint interrupt */ +#define USB_OTG_INCOMISOIN_INT ((uint32_t)0x00100000) /*!< usb otg incomplete isochronous in transfer interrupt */ +#define USB_OTG_INCOMPIP_INCOMPISOOUT_INT ((uint32_t)0x00200000) /*!< usb otg incomplete periodic transfer/isochronous out interrupt */ +#define USB_OTG_PRT_INT ((uint32_t)0x01000000) /*!< usb otg host port interrupt */ +#define USB_OTG_HCH_INT ((uint32_t)0x02000000) /*!< usb otg host channel interrupt */ +#define USB_OTG_PTXFEMP_INT ((uint32_t)0x04000000) /*!< usb otg periodic txfifo empty interrupt */ +#define USB_OTG_CONIDSCHG_INT ((uint32_t)0x10000000) /*!< usb otg connector id status change interrupt */ +#define USB_OTG_DISCON_INT ((uint32_t)0x20000000) /*!< usb otg disconnect detected interrupt */ +#define USB_OTG_WKUP_INT ((uint32_t)0x80000000) /*!< usb otg wakeup interrupt */ + +/** + * @} + */ + +/** @defgroup USB_global_interrupt_flags_definition + * @brief usb global interrupt flag + * @{ + */ + +#define USB_OTG_CURMODE ((uint32_t)0x00000001) /*!< usb otg current mode */ +#define USB_OTG_MODEMIS_FLAG ((uint32_t)0x00000002) /*!< usb otg mode mismatch flag */ +#define USB_OTG_OTGINT_FLAG ((uint32_t)0x00000004) /*!< usb otg flag */ +#define USB_OTG_SOF_FLAG ((uint32_t)0x00000008) /*!< usb otg sof flag */ +#define USB_OTG_RXFLVL_FLAG ((uint32_t)0x00000010) /*!< usb otg receive fifo non-empty flag */ +#define USB_OTG_NPTXFEMP_FLAG ((uint32_t)0x00000020) /*!< usb otg non-periodic tx fifo empty flag */ +#define USB_OTG_GINNAKEFF_FLAG ((uint32_t)0x00000040) /*!< usb otg global non-periodic in nak effective flag */ +#define USB_OTG_GOUTNAKEFF_FLAG ((uint32_t)0x00000080) /*!< usb otg global out nak effective flag */ +#define USB_OTG_ERLYSUSP_FLAG ((uint32_t)0x00000400) /*!< usb otg early suspend flag */ +#define USB_OTG_USBSUSP_FLAG ((uint32_t)0x00000800) /*!< usb otg suspend flag */ +#define USB_OTG_USBRST_FLAG ((uint32_t)0x00001000) /*!< usb otg reset flag */ +#define USB_OTG_ENUMDONE_FLAG ((uint32_t)0x00002000) /*!< usb otg enumeration done flag */ +#define USB_OTG_ISOOUTDROP_FLAG ((uint32_t)0x00004000) /*!< usb otg isochronous out packet dropped flag */ +#define USB_OTG_EOPF_FLAG ((uint32_t)0x00008000) /*!< usb otg eop flag */ +#define USB_OTG_IEPT_FLAG ((uint32_t)0x00040000) /*!< usb otg in endpoint flag */ +#define USB_OTG_OEPT_FLAG ((uint32_t)0x00080000) /*!< usb otg out endpoint flag */ +#define USB_OTG_INCOMISOIN_FLAG ((uint32_t)0x00100000) /*!< usb otg incomplete isochronous in transfer flag */ +#define USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG ((uint32_t)0x00200000) /*!< usb otg incomplete periodic transfer/isochronous out flag */ +#define USB_OTG_PRT_FLAG ((uint32_t)0x01000000) /*!< usb otg host port flag */ +#define USB_OTG_HCH_FLAG ((uint32_t)0x02000000) /*!< usb otg host channel flag */ +#define USB_OTG_PTXFEMP_FLAG ((uint32_t)0x04000000) /*!< usb otg periodic txfifo empty flag */ +#define USB_OTG_CONIDSCHG_FLAG ((uint32_t)0x10000000) /*!< usb otg connector id status change flag */ +#define USB_OTG_DISCON_FLAG ((uint32_t)0x20000000) /*!< usb otg disconnect detected flag */ +#define USB_OTG_WKUP_FLAG ((uint32_t)0x80000000) /*!< usb otg wakeup flag */ + +/** + * @} + */ + + +/** @defgroup USB_global_setting_definition + * @brief usb global setting + * @{ + */ + +/** + * @brief usb turnaround time + */ +#define USB_TRDTIM_8 0x9 /*!< usb turn around time 8 */ +#define USB_TRDTIM_16 0x5 /*!< usb turn around time 16 */ + +/** + * @brief usb receive status + */ +#define USB_OTG_GRXSTSP_EPTNUM ((uint32_t)0x0000000F) /*!< usb device receive packet endpoint number*/ +#define USB_OTG_GRXSTSP_CHNUM ((uint32_t)0x0000000F) /*!< usb host receive packet channel number*/ +#define USB_OTG_GRXSTSP_BCNT ((uint32_t)0x00007FF0) /*!< usb receive packet byte count */ +#define USB_OTG_GRXSTSP_DPID ((uint32_t)0x00018000) /*!< usb receive packet pid */ +#define USB_OTG_GRXSTSP_PKTSTS ((uint32_t)0x001E0000) /*!< usb receive packet status */ + +/** + * @brief usb host packet status + */ +#define PKTSTS_IN_DATA_PACKET_RECV 0x2 /*!< usb host in data packet received */ +#define PKTSTS_IN_TRANSFER_COMPLETE 0x3 /*!< usb host in transfer completed */ +#define PKTSTS_DATA_BIT_ERROR 0x5 /*!< usb host data toggle error */ +#define PKTSTS_CHANNEL_STOP 0x7 /*!< usb host channel halted */ + +/** + * @brief usb device packet status + */ +#define USB_OUT_STS_NAK 0x1 /*!< usb device global out nak */ +#define USB_OUT_STS_DATA 0x2 /*!< usb device out data packet received */ +#define USB_OUT_STS_COMP 0x3 /*!< usb device out transfer completed */ +#define USB_SETUP_STS_COMP 0x4 /*!< usb device setup transcation completed */ +#define USB_SETUP_STS_DATA 0x6 /*!< usb device setup data packet received */ + +/** + * @} + */ + +/** @defgroup USB_host_config_definition + * @{ + */ + +/** + * @brief usb host phy clock + */ +#define USB_HCFG_CLK_60M 0 /*!< usb host phy clock 60mhz */ +#define USB_HCFG_CLK_48M 1 /*!< usb host phy clock 48mhz */ +#define USB_HCFG_CLK_6M 2 /*!< usb host phy clock 6mhz */ + +/** + * @brief usb host port status + */ +#define USB_OTG_HPRT_PRTCONSTS ((uint32_t)0x00000001) /*!< usb host port connect status */ +#define USB_OTG_HPRT_PRTCONDET ((uint32_t)0x00000002) /*!< usb host port connect detected */ +#define USB_OTG_HPRT_PRTENA ((uint32_t)0x00000004) /*!< usb host port enable */ +#define USB_OTG_HPRT_PRTENCHNG ((uint32_t)0x00000008) /*!< usb host port enable/disable change */ +#define USB_OTG_HPRT_PRTOVRCACT ((uint32_t)0x00000010) /*!< usb host port overcurrent active */ +#define USB_OTG_HPRT_PRTOVRCCHNG ((uint32_t)0x00000020) /*!< usb host port overcurrent change */ +#define USB_OTG_HPRT_PRTRES ((uint32_t)0x00000040) /*!< usb host port resume */ +#define USB_OTG_HPRT_PRTSUSP ((uint32_t)0x00000080) /*!< usb host port suspend */ +#define USB_OTG_HPRT_PRTRST ((uint32_t)0x00000100) /*!< usb host port reset */ +#define USB_OTG_HPRT_PRTLNSTS ((uint32_t)0x00000C00) /*!< usb host port line status */ +#define USB_OTG_HPRT_PRTPWR ((uint32_t)0x00001000) /*!< usb host port power */ +#define USB_OTG_HPRT_PRTSPD ((uint32_t)0x00060000) /*!< usb host port speed */ + +/** + * @brief usb port speed + */ +#define USB_PRTSPD_HIGH_SPEED 0 /*!< usb host port high speed */ +#define USB_PRTSPD_FULL_SPEED 1 /*!< usb host port full speed */ +#define USB_PRTSPD_LOW_SPEED 2 /*!< usb host port low speed */ + +/** + * @brief usb host register hcchar bit define + */ +#define USB_OTG_HCCHAR_MPS ((uint32_t)0x000007FF) /*!< channel maximum packet size */ +#define USB_OTG_HCCHAR_EPTNUM ((uint32_t)0x00007800) /*!< endpoint number */ +#define USB_OTG_HCCHAR_EPTDIR ((uint32_t)0x00008000) /*!< endpoint direction */ +#define USB_OTG_HCCHAR_LSPDDEV ((uint32_t)0x00020000) /*!< low speed device */ +#define USB_OTG_HCCHAR_EPTYPE ((uint32_t)0x000C0000) /*!< endpoint type */ +#define USB_OTG_HCCHAR_MC ((uint32_t)0x00300000) /*!< multi count */ +#define USB_OTG_HCCHAR_DEVADDR ((uint32_t)0x1FC00000) /*!< device address */ +#define USB_OTG_HCCHAR_ODDFRM ((uint32_t)0x20000000) /*!< odd frame */ +#define USB_OTG_HCCHAR_CHDIS ((uint32_t)0x40000000) /*!< channel disable */ +#define USB_OTG_HCCHAR_CHENA ((uint32_t)0x80000000) /*!< channel enable */ + +/** + * @brief usb host register hctsiz bit define + */ +#define USB_OTG_HCTSIZ_XFERSIZE ((uint32_t)0x0007FFFF) /*!< channel transfer size */ +#define USB_OTG_HCTSIZ_PKTCNT ((uint32_t)0x1FF80000) /*!< channel packet count */ +#define USB_OTG_HCTSIZ_PID ((uint32_t)0x60000000) /*!< channel pid */ + +/** + * @brief usb host channel interrupt mask + */ +#define USB_OTG_HC_XFERCM_INT ((uint32_t)0x00000001) /*!< channel transfer complete interrupt */ +#define USB_OTG_HC_CHHLTDM_INT ((uint32_t)0x00000002) /*!< channel halted interrupt */ +#define USB_OTG_HC_STALLM_INT ((uint32_t)0x00000008) /*!< channel stall interrupt */ +#define USB_OTG_HC_NAKM_INT ((uint32_t)0x00000010) /*!< channel nak interrupt */ +#define USB_OTG_HC_ACKM_INT ((uint32_t)0x00000020) /*!< channel ack interrupt */ +#define USB_OTG_HC_NYETM_INT ((uint32_t)0x00000040) /*!< channel nyet interrupt */ +#define USB_OTG_HC_XACTERRM_INT ((uint32_t)0x00000080) /*!< channel transaction error interrupt */ +#define USB_OTG_HC_BBLERRM_INT ((uint32_t)0x00000100) /*!< channel babble error interrupt */ +#define USB_OTG_HC_FRMOVRRUN_INT ((uint32_t)0x00000200) /*!< channel frame overrun interrupt */ +#define USB_OTG_HC_DTGLERRM_INT ((uint32_t)0x00000400) /*!< channel data toggle interrupt */ + +/** + * @brief usb host channel interrupt flag + */ +#define USB_OTG_HC_XFERC_FLAG ((uint32_t)0x00000001) /*!< channel transfer complete flag */ +#define USB_OTG_HC_CHHLTD_FLAG ((uint32_t)0x00000002) /*!< channel halted flag */ +#define USB_OTG_HC_STALL_FLAG ((uint32_t)0x00000008) /*!< channel stall flag */ +#define USB_OTG_HC_NAK_FLAG ((uint32_t)0x00000010) /*!< channel nak flag */ +#define USB_OTG_HC_ACK_FLAG ((uint32_t)0x00000020) /*!< channel ack flag */ +#define USB_OTG_HC_NYET_FLAG ((uint32_t)0x00000040) /*!< channel nyet flag */ +#define USB_OTG_HC_XACTERR_FLAG ((uint32_t)0x00000080) /*!< channel transaction error flag */ +#define USB_OTG_HC_BBLERR_FLAG ((uint32_t)0x00000100) /*!< channel babble error flag */ +#define USB_OTG_HC_FRMOVRRUN_FLAG ((uint32_t)0x00000200) /*!< channel frame overrun flag */ +#define USB_OTG_HC_DTGLERR_FLAG ((uint32_t)0x00000400) /*!< channel data toggle flag */ + +/** + * @} + */ + + +/** @defgroup USB_device_config_definition + * @{ + */ +/** + * @brief usb device periodic frame interval + */ +typedef enum +{ + DCFG_PERFRINT_80 = 0x00, /*!< periodic frame interval 80% */ + DCFG_PERFRINT_85 = 0x01, /*!< periodic frame interval 85% */ + DCFG_PERFRINT_90 = 0x02, /*!< periodic frame interval 90% */ + DCFG_PERFRINT_95 = 0x03 /*!< periodic frame interval 95% */ +} dcfg_perfrint_type; + + +/** + * @brief usb device full speed + */ +#define USB_DCFG_FULL_SPEED 3 /*!< device full speed */ + +/** + * @brief usb device ctrl define + */ +#define USB_OTG_DCTL_RWKUPSIG ((uint32_t)0x00000001) /*!< usb device remote wakeup signaling */ +#define USB_OTG_DCTL_SFTDISCON ((uint32_t)0x00000002) /*!< usb device soft disconnect */ +#define USB_OTG_DCTL_GNPINNAKSTS ((uint32_t)0x00000004) /*!< usb device global non-periodic in nak status */ +#define USB_OTG_DCTL_GOUTNAKSTS ((uint32_t)0x00000008) /*!< usb device global out nak status */ +#define USB_OTG_DCTL_SGNPINNAK ((uint32_t)0x00000080) /*!< usb device set global non-periodic in nak */ +#define USB_OTG_DCTL_CGNPINNAK ((uint32_t)0x00000100) /*!< usb device clear global non-periodic in nak */ +#define USB_OTG_DCTL_SGOUTNAK ((uint32_t)0x00000200) /*!< usb device set global out nak status */ +#define USB_OTG_DCTL_CGOUTNAK ((uint32_t)0x00000400) /*!< usb device clear global out nak status */ +#define USB_OTG_DCTL_PWROPRGDNE ((uint32_t)0x00000800) /*!< usb device power on programming done */ + +/** + * @brief usb device in endpoint flag + */ +#define USB_OTG_DIEPINT_XFERC_FLAG ((uint32_t)0x00000001) /*!< usb device in transfer completed flag */ +#define USB_OTG_DIEPINT_EPTDISD_FLAG ((uint32_t)0x00000002) /*!< usb device endpoint disable flag */ +#define USB_OTG_DIEPINT_TIMEOUT_FLAG ((uint32_t)0x00000008) /*!< usb device in timeout */ +#define USB_OTG_DIEPINT_INTKNTXFEMP_FLAG ((uint32_t)0x00000010) /*!< usb device in token received when tx fifo is empty flag */ +#define USB_OTG_DIEPINT_INEPTNAK_FLAG ((uint32_t)0x00000040) /*!< usb device in endpoint nak effective flag */ +#define USB_OTG_DIEPINT_TXFEMP_FLAG ((uint32_t)0x00000080) /*!< usb device transmit fifo empty flag */ + +/** + * @brief usb device out endpoint flag + */ +#define USB_OTG_DOEPINT_XFERC_FLAG ((uint32_t)0x00000001) /*!< usb device out transfer completed flag */ +#define USB_OTG_DOEPINT_EPTDISD_FLAG ((uint32_t)0x00000002) /*!< usb device endpoint disable flag */ +#define USB_OTG_DOEPINT_SETUP_FLAG ((uint32_t)0x00000008) /*!< usb device setup flag */ +#define USB_OTG_DOEPINT_OUTTEPD_FLAG ((uint32_t)0x00000010) /*!< usb device out token recevied when endpoint disable flag */ +#define USB_OTG_DOEPINT_B2BSTUP_FLAG ((uint32_t)0x00000040) /*!< back-to-back setup packets received */ + +/** + * @brief usb device in endpoint fifo space mask + */ +#define USB_OTG_DTXFSTS_INEPTFSAV ((uint32_t)0x0000FFFF) /*!< usb device in endpoint tx fifo space avail */ + +/** + * @brief endpoint0 maximum packet size + */ +#define USB_EPT0_MPS_64 0 /*!< usb device endpoint 0 maximum packet size 64byte */ +#define USB_EPT0_MPS_32 1 /*!< usb device endpoint 0 maximum packet size 32byte */ +#define USB_EPT0_MPS_16 2 /*!< usb device endpoint 0 maximum packet size 16byte */ +#define USB_EPT0_MPS_8 3 /*!< usb device endpoint 0 maximum packet size 8byte */ + +/** + * @} + */ + +/** + * @brief otg fifo size (word) + */ +#define OTG_FIFO_SIZE 320 /*!< otg usb total fifo size */ + +/** + * @brief otg host max buffer length (byte) + */ +#define USB_MAX_DATA_LENGTH 0x200 /*!< usb host maximum buffer size */ + +#define OTGFS_USB_GLOBAL +#define OTGFS_USB_DEVICE +#define OTGFS_USB_HOST + +/** @defgroup USB_exported_enum_types + * @{ + */ + +/** + * @brief usb mode define(device, host, drd) + */ +typedef enum +{ + OTG_DEVICE_MODE, /*!< usb device mode */ + OTG_HOST_MODE, /*!< usb host mode */ + OTG_DRD_MODE /*!< usb drd mode */ +} otg_mode_type; + +/** + * @brief endpoint type define + */ +typedef enum +{ + EPT_CONTROL_TYPE = 0x00, /*!< usb endpoint type control */ + EPT_ISO_TYPE = 0x01, /*!< usb endpoint type iso */ + EPT_BULK_TYPE = 0x02, /*!< usb endpoint type bulk */ + EPT_INT_TYPE = 0x03 /*!< usb endpoint type interrupt */ +} endpoint_trans_type; + +/** + * @brief usb endpoint number define type + */ +typedef enum +{ + USB_EPT0 = 0x00, /*!< usb endpoint 0 */ + USB_EPT1 = 0x01, /*!< usb endpoint 1 */ + USB_EPT2 = 0x02, /*!< usb endpoint 2 */ + USB_EPT3 = 0x03, /*!< usb endpoint 3 */ + USB_EPT4 = 0x04, /*!< usb endpoint 4 */ + USB_EPT5 = 0x05, /*!< usb endpoint 5 */ + USB_EPT6 = 0x06, /*!< usb endpoint 6 */ + USB_EPT7 = 0x07 /*!< usb endpoint 7 */ +} usb_endpoint_number_type; + +/** + * @brief usb endpoint max num define + */ +#ifndef USB_EPT_MAX_NUM +#define USB_EPT_MAX_NUM 8 /*!< usb device support endpoint number */ +#endif +/** + * @brief usb channel max num define + */ +#ifndef USB_HOST_CHANNEL_NUM +#define USB_HOST_CHANNEL_NUM 16 /*!< usb host support channel number */ +#endif + +/** + * @brief endpoint trans dir type + */ +typedef enum +{ + EPT_DIR_IN = 0x00, /*!< usb transfer direction in */ + EPT_DIR_OUT = 0x01 /*!< usb transfer direction out */ +} endpoint_dir_type; + +/** + * @brief otgfs1 and otgfs2 select type + */ +typedef enum +{ + USB_OTG1_ID, /*!< usb otg 1 id */ + USB_OTG2_ID /*!< usb otg 2 id */ +} otg_id_type; + +/** + * @brief usb clock select + */ +typedef enum +{ + USB_CLK_HICK, /*!< usb clock use hick */ + USB_CLK_HEXT /*!< usb clock use hext */ +}usb_clk48_s; + +/** + * @} + */ + + + +/** @defgroup USB_exported_types + * @{ + */ + +/** + * @brief usb endpoint infomation structure definition + */ +typedef struct +{ + uint8_t eptn; /*!< endpoint register number (0~7) */ + uint8_t ept_address; /*!< endpoint address */ + uint8_t inout; /*!< endpoint dir EPT_DIR_IN or EPT_DIR_OUT */ + uint8_t trans_type; /*!< endpoint type: + EPT_CONTROL_TYPE, EPT_BULK_TYPE, EPT_INT_TYPE, EPT_ISO_TYPE*/ + uint16_t tx_addr; /*!< endpoint tx buffer offset address */ + uint16_t rx_addr; /*!< endpoint rx buffer offset address */ + uint32_t maxpacket; /*!< endpoint max packet*/ + uint8_t is_double_buffer; /*!< endpoint double buffer flag */ + uint8_t stall; /*!< endpoint is stall state */ + uint32_t status; + + /* transmission buffer and count */ + uint8_t *trans_buf; /*!< endpoint transmission buffer */ + uint32_t total_len; /*!< endpoint transmission lengtg */ + uint32_t trans_len; /*!< endpoint transmission length*/ + + uint32_t last_len; /*!< last transfer length */ + uint32_t rem0_len; /*!< rem transfer length */ + uint32_t ept0_slen; /*!< endpoint 0 transfer sum length */ +} usb_ept_info; + + +/** + * @brief usb host channel infomation structure definition + */ +typedef struct +{ + uint8_t ch_num; /*!< host channel number */ + uint8_t address; /*!< device address */ + uint8_t dir; /*!< transmission direction */ + uint8_t ept_num; /*!< device endpoint number */ + uint8_t ept_type; /*!< channel transmission type */ + uint32_t maxpacket; /*!< support max packet size */ + uint8_t data_pid; /*!< data pid */ + uint8_t speed; /*!< usb speed */ + uint8_t stall; /*!< channel stall flag */ + uint32_t status; /*!< channel status */ + uint32_t state; /*!< channel state */ + uint32_t urb_sts; /*!< usb channel request block state */ + + uint8_t toggle_in; /*!< channel in transfer toggle */ + uint8_t toggle_out; /*!< channel out transfer toggle */ + + /* transmission buffer and count */ + uint8_t *trans_buf; /* host channel buffer */ + uint32_t trans_len; /* host channel transmission len */ + uint32_t trans_count; /* host channel transmission count*/ +} usb_hch_type; + + +typedef struct +{ + /** + * @brief otgfs control and status register, offset:0x00 + */ + union + { + __IO uint32_t gotgctrl; + struct + { + __IO uint32_t reserved1 : 16; /* [15:0] */ + __IO uint32_t cidsts : 1; /* [16] */ + __IO uint32_t reserved2 : 4; /* [20:17] */ + __IO uint32_t curmod : 1; /* [21] */ + __IO uint32_t reserved3 : 10; /* [31:22] */ + } gotgctrl_bit; + }; + + /** + * @brief otgfs interrupt register, offset:0x04 + */ + union + { + __IO uint32_t gotgint; + struct + { + __IO uint32_t reserved1 : 2; /* [1:0] */ + __IO uint32_t sesenddet : 1; /* [2] */ + __IO uint32_t reserved2 : 29; /* [31:3] */ + + } gotgint_bit; + }; + + /** + * @brief otgfs gahbcfg configuration register, offset:0x08 + */ + union + { + __IO uint32_t gahbcfg; + struct + { + __IO uint32_t glbintmsk : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t nptxfemplvl : 1; /* [7] */ + __IO uint32_t ptxfemplvl : 1; /* [8] */ + __IO uint32_t reserved2 : 23; /* [31:9] */ + } gahbcfg_bit; + }; + + /** + * @brief otgfs usb configuration register, offset:0x0C + */ + union + { + __IO uint32_t gusbcfg; + struct + { + __IO uint32_t toutcal : 3; /* [2:0] */ + __IO uint32_t reserved1 : 7; /* [9:3] */ + __IO uint32_t usbtrdtim : 4; /* [13:10] */ + __IO uint32_t reserved2 : 15; /* [28:14] */ + __IO uint32_t fhstmode : 1; /* [29] */ + __IO uint32_t fdevmode : 1; /* [30] */ + __IO uint32_t cotxpkt : 1; /* [31] */ + } gusbcfg_bit; + }; + + /** + * @brief otgfs reset register, offset:0x10 + */ + union + { + __IO uint32_t grstctl; + struct + { + __IO uint32_t csftrst : 1; /* [0] */ + __IO uint32_t piusftrst : 1; /* [1] */ + __IO uint32_t frmcntrst : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t rxfflsh : 1; /* [4] */ + __IO uint32_t txfflsh : 1; /* [5] */ + __IO uint32_t txfnum : 5; /* [10:6] */ + __IO uint32_t reserved2 : 20; /* [30:11] */ + __IO uint32_t ahbidle : 1; /* [31] */ + } grstctl_bit; + }; + + /** + * @brief otgfs core interrupt register, offset:0x14 + */ + union + { + __IO uint32_t gintsts; + struct + { + __IO uint32_t curmode : 1; /* [0] */ + __IO uint32_t modemis : 1; /* [1] */ + __IO uint32_t otgint : 1; /* [2] */ + __IO uint32_t sof : 1; /* [3] */ + __IO uint32_t rxflvl : 1; /* [4] */ + __IO uint32_t nptxfemp : 1; /* [5] */ + __IO uint32_t ginnakeff : 1; /* [6] */ + __IO uint32_t goutnakeff : 1; /* [7] */ + __IO uint32_t reserved1 : 2; /* [9:8]] */ + __IO uint32_t erlysusp : 1; /* [10] */ + __IO uint32_t usbsusp : 1; /* [11] */ + __IO uint32_t usbrst : 1; /* [12] */ + __IO uint32_t enumdone : 1; /* [13] */ + __IO uint32_t isooutdrop : 1; /* [14] */ + __IO uint32_t eopf : 1; /* [15] */ + __IO uint32_t reserved2 : 2; /* [17:16]] */ + __IO uint32_t ieptint : 1; /* [18] */ + __IO uint32_t oeptint : 1; /* [19] */ + __IO uint32_t incompisoin : 1; /* [20] */ + __IO uint32_t incompip_incompisoout : 1; /* [21] */ + __IO uint32_t reserved3 : 2; /* [23:22] */ + __IO uint32_t prtint : 1; /* [24] */ + __IO uint32_t hchint : 1; /* [25] */ + __IO uint32_t ptxfemp : 1; /* [26] */ + __IO uint32_t reserved4 : 1; /* [27] */ + __IO uint32_t conidschg : 1; /* [28] */ + __IO uint32_t disconint : 1; /* [29] */ + __IO uint32_t reserved5 : 1; /* [30] */ + __IO uint32_t wkupint : 1; /* [31] */ + } gintsts_bit; + }; + + /** + * @brief otgfs interrupt mask register, offset:0x18 + */ + union + { + __IO uint32_t gintmsk; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t modemismsk : 1; /* [1] */ + __IO uint32_t otgintmsk : 1; /* [2] */ + __IO uint32_t sofmsk : 1; /* [3] */ + __IO uint32_t rxflvlmsk : 1; /* [4] */ + __IO uint32_t nptxfempmsk : 1; /* [5] */ + __IO uint32_t ginnakeffmsk : 1; /* [6] */ + __IO uint32_t goutnakeffmsk : 1; /* [7] */ + __IO uint32_t reserved2 : 2; /* [9:8]] */ + __IO uint32_t erlysuspmsk : 1; /* [10] */ + __IO uint32_t usbsuspmsk : 1; /* [11] */ + __IO uint32_t usbrstmsk : 1; /* [12] */ + __IO uint32_t enumdonemsk : 1; /* [13] */ + __IO uint32_t isooutdropmsk : 1; /* [14] */ + __IO uint32_t eopfmsk : 1; /* [15] */ + __IO uint32_t reserved3 : 2; /* [17:16]] */ + __IO uint32_t ieptintmsk : 1; /* [18] */ + __IO uint32_t oeptintmsk : 1; /* [19] */ + __IO uint32_t incompisoinmsk : 1; /* [20] */ + __IO uint32_t incompip_incompisooutmsk : 1; /* [21] */ + __IO uint32_t reserved4 : 2; /* [23:22] */ + __IO uint32_t prtintmsk : 1; /* [24] */ + __IO uint32_t hchintmsk : 1; /* [25] */ + __IO uint32_t ptxfempmsk : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t conidschgmsk : 1; /* [28] */ + __IO uint32_t disconintmsk : 1; /* [29] */ + __IO uint32_t reserved6 : 1; /* [30] */ + __IO uint32_t wkupintmsk : 1; /* [31] */ + } gintmsk_bit; + }; + + /** + * @brief otgfs rx status debug read register, offset:0x1C + */ + union + { + __IO uint32_t grxstsr; + struct + { + __IO uint32_t eptnum : 4; /* [3:0] */ + __IO uint32_t bcnt : 11; /* [14:4] */ + __IO uint32_t dpid : 2; /* [16:15] */ + __IO uint32_t pktsts : 4; /* [20:17] */ + __IO uint32_t fn : 4; /* [24:21] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } grxstsr_bit; + }; + + /** + * @brief otgfs rx status read and pop register, offset:0x20 + */ + union + { + __IO uint32_t grxstsp; + struct + { + __IO uint32_t chnum : 4; /* [3:0] */ + __IO uint32_t bcnt : 11; /* [14:4] */ + __IO uint32_t dpid : 2; /* [16:15] */ + __IO uint32_t pktsts : 4; /* [20:17] */ + __IO uint32_t reserved1 : 11; /* [31:21] */ + } grxstsp_bit; + }; + + /** + * @brief otgfs rx fifo size register, offset:0x24 + */ + union + { + __IO uint32_t grxfsiz; + struct + { + __IO uint32_t rxfdep : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } grxfsiz_bit; + }; + + /** + * @brief otgfs non-periodic and ept0 tx fifo size register, offset:0x28 + */ + union + { + __IO uint32_t gnptxfsiz_ept0tx; + struct + { + __IO uint32_t nptxfstaddr : 16; /* [15:0] */ + __IO uint32_t nptxfdep : 16; /* [31:16] */ + } gnptxfsiz_ept0tx_bit; + }; + + /** + * @brief otgfs non-periodic tx fifo request queue status register, offset:0x2C + */ + union + { + __IO uint32_t gnptxsts; + struct + { + __IO uint32_t nptxfspcavail : 16; /* [15:0] */ + __IO uint32_t nptxqspcavail : 8; /* [23:16] */ + __IO uint32_t nptxqtop : 7; /* [30:24] */ + } gnptxsts_bit; + }; + + __IO uint32_t reserved2[2]; + + /** + * @brief otgfs general core configuration register, offset:0x38 + */ + union + { + __IO uint32_t gccfg; + struct + { + __IO uint32_t reserved1 : 16; /* [15:0] */ + __IO uint32_t pwrdown : 1; /* [16] */ + __IO uint32_t lp_mode : 1; /* [17] */ + __IO uint32_t reserved2 : 2; /* [19:18] */ + __IO uint32_t sofouten : 1; /* [20] */ + __IO uint32_t vbusig : 1; /* [21] */ + __IO uint32_t reserved3 : 10; /* [31:22] */ + } gccfg_bit; + }; + + /** + * @brief otgfs core id register, offset:0x3C + */ + union + { + __IO uint32_t guid; + struct + { + __IO uint32_t userid : 32; /* [31:0] */ + } guid_bit; + }; + + __IO uint32_t reserved3[48]; + + /** + * @brief otgfs host periodic tx fifo size register, offset:0x100 + */ + union + { + __IO uint32_t hptxfsiz; + struct + { + __IO uint32_t ptxfstaddr : 16; /* [15:0] */ + __IO uint32_t ptxfsize : 16; /* [31:16] */ + } hptxfsiz_bit; + }; + + /** + * @brief otgfs host periodic tx fifo size register, offset:0x100 + */ + union + { + __IO uint32_t dieptxfn[7]; + struct + { + __IO uint32_t ineptxfstaddr : 16; /* [15:0] */ + __IO uint32_t ineptxfdep : 16; /* [31:16] */ + } dieptxfn_bit[7]; + }; +} otg_global_type; + + +typedef struct +{ + /** + * @brief otgfs host mode configuration register, offset:0x400 + */ + union + { + __IO uint32_t hcfg; + struct + { + __IO uint32_t fslspclksel : 2; /* [1:0] */ + __IO uint32_t fslssupp : 1; /* [2] */ + __IO uint32_t reserved1 : 29; /* [31:3] */ + } hcfg_bit; + }; + + /** + * @brief otgfs host frame interval register, offset:0x404 + */ + union + { + __IO uint32_t hfir; + struct + { + __IO uint32_t frint : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:15] */ + } hfir_bit; + }; + + /** + * @brief otgfs host frame number and time remaining register, offset:0x408 + */ + union + { + __IO uint32_t hfnum; + struct + { + __IO uint32_t frnum : 16; /* [15:0] */ + __IO uint32_t ftrem : 16; /* [31:15] */ + } hfnum_bit; + }; + + __IO uint32_t reserved1; + + /** + * @brief otgfs host periodic tx fifo request queue register, offset:0x410 + */ + union + { + __IO uint32_t hptxsts; + struct + { + __IO uint32_t ptxfspcavil : 16; /* [15:0] */ + __IO uint32_t ptxqspcavil : 8; /* [23:16] */ + __IO uint32_t ptxqtop : 8; /* [31:24] */ + } hptxsts_bit; + }; + + /** + * @brief otgfs host all channel interrupt register, offset:0x414 + */ + union + { + __IO uint32_t haint; + struct + { + __IO uint32_t haint : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [32:16] */ + } haint_bit; + }; + + /** + * @brief otgfs host all channel interrupt mask register, offset:0x418 + */ + union + { + __IO uint32_t haintmsk; + struct + { + __IO uint32_t haintmsk : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [32:16] */ + } haintmsk_bit; + }; + + __IO uint32_t reserved2[9]; + + /** + * @brief otgfs host port control and status register, offset:0x440 + */ + union + { + __IO uint32_t hprt; + struct + { + __IO uint32_t prtconsts : 1; /* [0] */ + __IO uint32_t prtcondet : 1; /* [1] */ + __IO uint32_t prtena : 1; /* [2] */ + __IO uint32_t prtenchng : 1; /* [3] */ + __IO uint32_t prtovrcact : 1; /* [4] */ + __IO uint32_t prtovrcchng : 1; /* [5] */ + __IO uint32_t prtres : 1; /* [6] */ + __IO uint32_t prtsusp : 1; /* [7] */ + __IO uint32_t prtrst : 1; /* [8] */ + __IO uint32_t reserved1 : 1; /* [9] */ + __IO uint32_t prtlnsts : 2; /* [11:10] */ + __IO uint32_t prtpwr : 1; /* [12] */ + __IO uint32_t prttsctl : 4; /* [16:13] */ + __IO uint32_t prtspd : 2; /* [18:17] */ + __IO uint32_t reserved2 : 13; /* [31:19] */ + + } hprt_bit; + }; +} otg_host_type; + +typedef struct +{ + /** + * @brief otgfs host channel x characterisic register, offset:0x500 + */ + union + { + __IO uint32_t hcchar; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t eptnum : 4; /* [14:11] */ + __IO uint32_t eptdir : 1; /* [15] */ + __IO uint32_t reserved1 : 1; /* [16] */ + __IO uint32_t lspddev : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t mc : 2; /* [21:20] */ + __IO uint32_t devaddr : 7; /* [28:22] */ + __IO uint32_t oddfrm : 1; /* [29] */ + __IO uint32_t chdis : 1; /* [30] */ + __IO uint32_t chena : 1; /* [31] */ + } hcchar_bit; + }; + + /** + * @brief otgfs host channel split control register, offset:0x504 + */ + union + { + __IO uint32_t hcsplt; + struct + { + __IO uint32_t prtaddr : 7; /* [6:0] */ + __IO uint32_t hubaddr : 7; /* [13:7] */ + __IO uint32_t xactpos : 2; /* [15:14] */ + __IO uint32_t compsplt : 1; /* [16] */ + __IO uint32_t reserved1 : 14; /* [30:17] */ + __IO uint32_t spltena : 1; /* [31] */ + } hcsplt_bit; + }; + + /** + * @brief otgfs host channel interrupt register, offset:0x508 + */ + union + { + __IO uint32_t hcint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t chhltd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t stall : 1; /* [3] */ + __IO uint32_t nak : 1; /* [4] */ + __IO uint32_t ack : 1; /* [5] */ + __IO uint32_t reserved2 : 1; /* [6] */ + __IO uint32_t xacterr : 1; /* [7] */ + __IO uint32_t bblerr : 1; /* [8] */ + __IO uint32_t frmovrun : 1; /* [9] */ + __IO uint32_t dtglerr : 1; /* [10] */ + __IO uint32_t reserved3 : 21; /* [31:11] */ + } hcint_bit; + }; + + /** + * @brief otgfs host channel interrupt mask register, offset:0x50C + */ + union + { + __IO uint32_t hcintmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t chhltdmsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t stallmsk : 1; /* [3] */ + __IO uint32_t nakmsk : 1; /* [4] */ + __IO uint32_t ackmsk : 1; /* [5] */ + __IO uint32_t reserved2 : 1; /* [6] */ + __IO uint32_t xacterrmsk : 1; /* [7] */ + __IO uint32_t bblerrmsk : 1; /* [8] */ + __IO uint32_t frmovrunmsk : 1; /* [9] */ + __IO uint32_t dtglerrmsk : 1; /* [10] */ + __IO uint32_t reserved3 : 21; /* [31:11] */ + } hcintmsk_bit; + }; + + /** + * @brief otgfs host channel transfer size register, offset:0x510 + */ + union + { + __IO uint32_t hctsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t pid : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } hctsiz_bit; + }; + __IO uint32_t reserved3[3]; + +}otg_hchannel_type; + + +typedef struct +{ + /** + * @brief otgfs device configuration register, offset:0x800 + */ + union + { + __IO uint32_t dcfg; + struct + { + __IO uint32_t devspd : 2; /* [1:0] */ + __IO uint32_t nzstsouthshk : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t devaddr : 7; /* [10:4] */ + __IO uint32_t perfrint : 2; /* [12:11] */ + __IO uint32_t reserved2 : 19; /* [31:13] */ + } dcfg_bit; + }; + + /** + * @brief otgfs device controls register, offset:0x804 + */ + union + { + __IO uint32_t dctl; + struct + { + __IO uint32_t rwkupsig : 1; /* [0] */ + __IO uint32_t sftdiscon : 1; /* [1] */ + __IO uint32_t gnpinnaksts : 1; /* [2] */ + __IO uint32_t goutnaksts : 1; /* [3] */ + __IO uint32_t tstctl : 3; /* [6:4] */ + __IO uint32_t sgnpinak : 1; /* [7] */ + __IO uint32_t cgnpinak : 1; /* [8] */ + __IO uint32_t sgoutnak : 1; /* [9] */ + __IO uint32_t cgoutnak : 1; /* [10] */ + __IO uint32_t pwroprgdne : 1; /* [11] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } dctl_bit; + }; + + /** + * @brief otgfs device status register, offset:0x80C + */ + union + { + __IO uint32_t dsts; + struct + { + __IO uint32_t suspsts : 1; /* [0] */ + __IO uint32_t enumspd : 2; /* [2:1] */ + __IO uint32_t eticerr : 1; /* [3] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t soffn : 14; /* [21:8] */ + __IO uint32_t reserved2 : 10; /* [31:22] */ + } dsts_bit; + }; + + __IO uint32_t reserved1; + /** + * @brief otgfs device in endpoint general interrupt mask register, offset:0x810 + */ + union + { + __IO uint32_t diepmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t eptdismsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t timeoutmsk : 1; /* [3] */ + __IO uint32_t intkntxfempmsk : 1; /* [4] */ + __IO uint32_t intkneptmismsk : 1; /* [5] */ + __IO uint32_t ineptnakmsk : 1; /* [6] */ + __IO uint32_t reserved2 : 1; /* [7] */ + __IO uint32_t txfifoudrmsk : 1; /* [8] */ + __IO uint32_t bnainmsk : 1; /* [9] */ + __IO uint32_t reserved3 : 22; /* [31:10] */ + } diepmsk_bit; + }; + + /** + * @brief otgfs device out endpoint general interrupt mask register, offset:0x814 + */ + union + { + __IO uint32_t doepmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t eptdismsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t setupmsk : 1; /* [3] */ + __IO uint32_t outtepdmsk : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t b2bsetupmsk : 1; /* [6] */ + __IO uint32_t reserved3 : 1; /* [7] */ + __IO uint32_t outperrmsk : 1; /* [8] */ + __IO uint32_t bnaoutmsk : 1; /* [9] */ + __IO uint32_t reserved4 : 22; /* [31:10] */ + } doepmsk_bit; + }; + + /** + * @brief otgfs device all endpoint interrupt register, offset:0x818 + */ + union + { + __IO uint32_t daint; + struct + { + __IO uint32_t ineptint : 16; /* [15:0] */ + __IO uint32_t outeptint : 16; /* [31:16] */ + } daint_bit; + }; + + /** + * @brief otgfs device all endpoint interrupt mask register, offset:0x81C + */ + union + { + __IO uint32_t daintmsk; + struct + { + __IO uint32_t ineptmsk : 16; /* [15:0] */ + __IO uint32_t outeptmsk : 16; /* [31:16] */ + } daintmsk_bit; + }; + + __IO uint32_t reserved2[5]; + + /** + * @brief otgfs device in endpoint fifo empty interrupt mask register, offset:0x834 + */ + union + { + __IO uint32_t diepempmsk; + struct + { + __IO uint32_t ineptxfemsk : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } diepempmsk_bit; + }; + +} otg_device_type; + +typedef struct +{ + /** + * @brief otgfs device out endpoint control register, offset:0x900 + */ + union + { + __IO uint32_t diepctl; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t usbacept : 1; /* [15] */ + __IO uint32_t dpid : 1; /* [16] */ + __IO uint32_t naksts : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t reserved2 : 1; /* [20] */ + __IO uint32_t stall : 1; /* [21] */ + __IO uint32_t txfnum : 4; /* [25:22] */ + __IO uint32_t cnak : 1; /* [26] */ + __IO uint32_t snak : 1; /* [27] */ + __IO uint32_t setd0pid : 1; /* [28] */ + __IO uint32_t setd1pid : 1; /* [29] */ + __IO uint32_t eptdis : 1; /* [30] */ + __IO uint32_t eptena : 1; /* [31] */ + } diepctl_bit; + }; + __IO uint32_t reserved1; + + /** + * @brief otgfs device in endpoint interrupt register, offset:0x908 + */ + union + { + __IO uint32_t diepint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t epdisd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t timeout : 1; /* [3] */ + __IO uint32_t intkntxfemp : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t ineptnak : 1; /* [6] */ + __IO uint32_t txfemp : 1; /* [7] */ + __IO uint32_t reserved3 : 24; /* [31:8] */ + } diepint_bit; + }; + __IO uint32_t reserved2; + + /** + * @brief otgfs device in endpoint transfer size register, offset:0x910 + endpoint number * 0x20 + */ + union + { + __IO uint32_t dieptsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t mc : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } dieptsiz_bit; + }; + + __IO uint32_t reserved3; + + /** + * @brief otgfs device in endpoint tx fifo status register, offset:0x918 + endpoint number * 0x20 + */ + union + { + __IO uint32_t dtxfsts; + struct + { + __IO uint32_t ineptxfsav : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } dtxfsts_bit; + }; + +} otg_eptin_type; + +typedef struct +{ + /** + * @brief otgfs device out endpoint control register, offset:0xb00 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doepctl; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t usbacept : 1; /* [15] */ + __IO uint32_t dpid : 1; /* [16] */ + __IO uint32_t naksts : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t snpm : 1; /* [20] */ + __IO uint32_t stall : 1; /* [21] */ + __IO uint32_t reserved2 : 4; /* [25:22] */ + __IO uint32_t cnak : 1; /* [26] */ + __IO uint32_t snak : 1; /* [27] */ + __IO uint32_t setd0pid : 1; /* [28] */ + __IO uint32_t setd1pid : 1; /* [29] */ + __IO uint32_t eptdis : 1; /* [30] */ + __IO uint32_t eptena : 1; /* [31] */ + } doepctl_bit; + }; + __IO uint32_t reserved1; + + /** + * @brief otgfs device out endpoint interrupt register, offset:0xb08 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doepint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t epdisd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t setup : 1; /* [3] */ + __IO uint32_t outtepd : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t b2pstup : 1; /* [6] */ + __IO uint32_t reserved3 : 25; /* [31:7] */ + } doepint_bit; + }; + __IO uint32_t reserved2; + + /** + * @brief otgfs device out endpoint transfer size register, offset:0xb10 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doeptsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t rxdpid_setupcnt : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } doeptsiz_bit; + }; +} otg_eptout_type; + +typedef struct +{ + /** + * @brief otgfs power and clock gating control registers, offset:0xe00 + */ + union + { + __IO uint32_t pcgcctl; + struct + { + __IO uint32_t stoppclk : 1; /* [0] */ + __IO uint32_t reserved1 : 3; /* [3:1] */ + __IO uint32_t suspendm : 1; /* [4] */ + __IO uint32_t reserved2 : 27; /* [31:5] */ + } pcgcctl_bit; + }; +} otg_pcgcctl_type; + +/** + * @} + */ + +/** @defgroup USB_exported_functions + * @{ + */ + +/** + * @brief usb host and device offset address + */ +#define OTG_HOST_ADDR_OFFSET 0x400 /*!< usb host register offset address */ +#define OTG_HOST_CHANNEL_ADDR_OFFSET 0x500 /*!< usb host channel register offset address */ +#define OTG_DEVICE_ADDR_OFFSET 0x800 /*!< usb device register offset address */ +#define OTG_DEVICE_EPTIN_ADDR_OFFSET 0x900 /*!< usb device endpoint in register offset address */ +#define OTG_DEVICE_EPTOUT_ADDR_OFFSET 0xB00 /*!< usb device endpoint out register offset address */ +#define OTG_PCGCCTL_ADDR_OFFSET 0xE00 /*!< usb power and clock control register offset address */ +#define OTG_FIFO_ADDR_OFFSET 0x1000 /*!< usb fifo offset address */ + +/** + * @brief usb host and device register define + */ +#define OTG1_GLOBAL ((otg_global_type *)(OTGFS1_BASE)) /*!< usb otg1 global register */ +#define OTG2_GLOBAL ((otg_global_type *)(OTGFS2_BASE)) /*!< usb otg2 global register */ +#define OTG_PCGCCTL(usbx) ((otg_pcgcctl_type *)((uint32_t)usbx + OTG_PCGCCTL_ADDR_OFFSET)) /*!< usb power and clock control register */ +#define OTG_DEVICE(usbx) ((otg_device_type *)((uint32_t)usbx + OTG_DEVICE_ADDR_OFFSET)) /*!< usb device register */ +#define OTG_HOST(usbx) ((otg_host_type *)((uint32_t)usbx + OTG_HOST_ADDR_OFFSET)) /*!< usb host register */ +#define USB_CHL(usbx, n) ((otg_hchannel_type *)((uint32_t)usbx + OTG_HOST_CHANNEL_ADDR_OFFSET + n * 0x20)) /*!< usb channel n register */ +#define USB_INEPT(usbx, eptn) ((otg_eptin_type *)((uint32_t)usbx + OTG_DEVICE_EPTIN_ADDR_OFFSET + eptn * 0x20)) /*!< usb device endpoint in register */ +#define USB_OUTEPT(usbx, eptn) ((otg_eptout_type *)((uint32_t)usbx + OTG_DEVICE_EPTOUT_ADDR_OFFSET + eptn * 0x20)) /*!< usb device endpoint out register */ +#define USB_FIFO(usbx, eptn) *(__IO uint32_t *)((uint32_t)usbx + OTG_FIFO_ADDR_OFFSET + eptn * 0x1000) /*!< usb fifo address */ + + + +typedef otg_global_type usb_reg_type; + +/** @defgroup USB_exported_functions + * @{ + */ + +#ifdef OTGFS_USB_GLOBAL +error_status usb_global_reset(otg_global_type *usbx); +void usb_global_init(otg_global_type *usbx); +otg_global_type *usb_global_select_core(uint8_t usb_id); +void usb_flush_tx_fifo(otg_global_type *usbx, uint32_t fifo_num); +void usb_flush_rx_fifo(otg_global_type *usbx); +void usb_global_interrupt_enable(otg_global_type *usbx, uint16_t interrupt, confirm_state new_state); +uint32_t usb_global_get_all_interrupt(otg_global_type *usbx); +void usb_global_clear_interrupt(otg_global_type *usbx, uint32_t flag); +void usb_interrupt_enable(otg_global_type *usbx); +void usb_interrupt_disable(otg_global_type *usbx); +void usb_set_rx_fifo(otg_global_type *usbx, uint16_t size); +void usb_set_tx_fifo(otg_global_type *usbx, uint8_t txfifo, uint16_t size); +void usb_global_set_mode(otg_global_type *usbx, uint32_t mode); +void usb_global_power_on(otg_global_type *usbx); +void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes); +void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes); +void usb_stop_phy_clk(otg_global_type *usbx); +void usb_open_phy_clk(otg_global_type *usbx); +#endif + +#ifdef OTGFS_USB_DEVICE +void usb_ept_open(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_close(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_stall(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_clear_stall(otg_global_type *usbx, usb_ept_info *ept_info); +uint32_t usb_get_all_out_interrupt(otg_global_type *usbx); +uint32_t usb_get_all_in_interrupt(otg_global_type *usbx); +uint32_t usb_ept_out_interrupt(otg_global_type *usbx, uint32_t eptn); +uint32_t usb_ept_in_interrupt(otg_global_type *usbx, uint32_t eptn); +void usb_ept_out_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag); +void usb_ept_in_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag); +void usb_set_address(otg_global_type *usbx, uint8_t address); +void usb_ept0_start(otg_global_type *usbx); +void usb_ept0_setup(otg_global_type *usbx); +void usb_connect(otg_global_type *usbx); +void usb_disconnect(otg_global_type *usbx); +void usb_remote_wkup_set(otg_global_type *usbx); +void usb_remote_wkup_clear(otg_global_type *usbx); +uint8_t usb_suspend_status_get(otg_global_type *usbx); +#endif + +#ifdef OTGFS_USB_HOST +void usb_port_power_on(otg_global_type *usbx, confirm_state state); +uint32_t usbh_get_frame(otg_global_type *usbx); +void usb_hc_enable(otg_global_type *usbx, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed); +uint32_t usb_hch_read_interrupt(otg_global_type *usbx); +void usb_host_disable(otg_global_type *usbx); +void usb_hch_halt(otg_global_type *usbx, uint8_t chn); +void usbh_fsls_clksel(otg_global_type *usbx, uint8_t clk); +#endif +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h new file mode 100644 index 0000000000..e0a509b61c --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h @@ -0,0 +1,197 @@ +/** + ************************************************************************** + * @file at32f435_437_wdt.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 wdt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_WDT_H +#define __AT32F435_437_WDT_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup WDT + * @{ + */ + + +/** @defgroup WDT_flags_definition + * @brief wdt flag + * @{ + */ + +#define WDT_DIVF_UPDATE_FLAG ((uint16_t)0x0001) /*!< wdt division value update complete flag */ +#define WDT_RLDF_UPDATE_FLAG ((uint16_t)0x0002) /*!< wdt reload value update complete flag */ +#define WDT_WINF_UPDATE_FLAG ((uint16_t)0x0004) /*!< wdt window value update complete flag */ + +/** + * @} + */ + +/** @defgroup WDT_exported_types + * @{ + */ + +/** + * @brief wdt division value type + */ +typedef enum +{ + WDT_CLK_DIV_4 = 0x00, /*!< wdt clock divider value is 4 */ + WDT_CLK_DIV_8 = 0x01, /*!< wdt clock divider value is 8 */ + WDT_CLK_DIV_16 = 0x02, /*!< wdt clock divider value is 16 */ + WDT_CLK_DIV_32 = 0x03, /*!< wdt clock divider value is 32 */ + WDT_CLK_DIV_64 = 0x04, /*!< wdt clock divider value is 64 */ + WDT_CLK_DIV_128 = 0x05, /*!< wdt clock divider value is 128 */ + WDT_CLK_DIV_256 = 0x06 /*!< wdt clock divider value is 256 */ +} wdt_division_type; + +/** + * @brief wdt cmd value type + */ +typedef enum +{ + WDT_CMD_LOCK = 0x0000, /*!< disable write protection command */ + WDT_CMD_UNLOCK = 0x5555, /*!< enable write protection command */ + WDT_CMD_ENABLE = 0xCCCC, /*!< enable wdt command */ + WDT_CMD_RELOAD = 0xAAAA /*!< reload command */ +} wdt_cmd_value_type; + +/** + * @brief type define wdt register all + */ +typedef struct +{ + + /** + * @brief wdt cmd register, offset:0x00 + */ + union + { + __IO uint32_t cmd; + struct + { + __IO uint32_t cmd : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cmd_bit; + }; + + /** + * @brief wdt div register, offset:0x04 + */ + union + { + __IO uint32_t div; + struct + { + __IO uint32_t div : 3; /* [2:0] */ + __IO uint32_t reserved1 : 29;/* [31:3] */ + } div_bit; + }; + + /** + * @brief wdt rld register, offset:0x08 + */ + union + { + __IO uint32_t rld; + struct + { + __IO uint32_t rld : 12;/* [11:0] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } rld_bit; + }; + + /** + * @brief wdt sts register, offset:0x0C + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t divf : 1; /* [0] */ + __IO uint32_t rldf : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } sts_bit; + }; + + /** + * @brief wdt win register, offset:0x10 + */ + union + { + __IO uint32_t win; + struct + { + __IO uint32_t win : 12;/* [11:0] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } win_bit; + }; +} wdt_type; + +/** + * @} + */ + +#define WDT ((wdt_type *) WDT_BASE) + +/** @defgroup WDT_exported_functions + * @{ + */ + +void wdt_enable(void); +void wdt_counter_reload(void); +void wdt_reload_value_set(uint16_t reload_value); +void wdt_divider_set(wdt_division_type division); +void wdt_register_write_enable( confirm_state new_state); +flag_status wdt_flag_get(uint16_t wdt_flag); +void wdt_window_counter_set(uint16_t window_cnt); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h new file mode 100644 index 0000000000..f7999c9eb9 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h @@ -0,0 +1,158 @@ +/** + ************************************************************************** + * @file at32f435_437_wwdt.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 wwdt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_WWDT_H +#define __AT32F435_437_WWDT_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup WWDT + * @{ + */ + +/** @defgroup WWDT_enable_bit_definition + * @brief wwdt enable bit + * @{ + */ + +#define WWDT_EN_BIT ((uint32_t)0x00000080) /*!< wwdt enable bit */ + +/** + * @} + */ + +/** @defgroup WWDT_exported_types + * @{ + */ + +/** + * @brief wwdt division type + */ +typedef enum +{ + WWDT_PCLK1_DIV_4096 = 0x00, /*!< wwdt counter clock = (pclk1/4096)/1) */ + WWDT_PCLK1_DIV_8192 = 0x01, /*!< wwdt counter clock = (pclk1/4096)/2) */ + WWDT_PCLK1_DIV_16384 = 0x02, /*!< wwdt counter clock = (pclk1/4096)/4) */ + WWDT_PCLK1_DIV_32768 = 0x03 /*!< wwdt counter clock = (pclk1/4096)/8) */ +} wwdt_division_type; + +/** + * @brief type define wwdt register all + */ +typedef struct +{ + + /** + * @brief wwdt ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t cnt : 7; /* [6:0] */ + __IO uint32_t wwdten : 1; /* [7] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } ctrl_bit; + }; + + /** + * @brief wwdt cfg register, offset:0x04 + */ + union + { + __IO uint32_t cfg; + struct + { + __IO uint32_t win : 7; /* [6:0] */ + __IO uint32_t div : 2; /* [8:7] */ + __IO uint32_t rldien : 1; /* [9] */ + __IO uint32_t reserved1 : 22;/* [31:10] */ + } cfg_bit; + }; + + /** + * @brief wwdt cfg register, offset:0x08 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t rldf : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } sts_bit; + }; + +} wwdt_type; + +/** + * @} + */ + +#define WWDT ((wwdt_type *) WWDT_BASE) + +/** @defgroup WWDT_exported_functions + * @{ + */ + +void wwdt_reset(void); +void wwdt_divider_set(wwdt_division_type division); +void wwdt_flag_clear(void); +void wwdt_enable(uint8_t wwdt_cnt); +void wwdt_interrupt_enable(void); +flag_status wwdt_flag_get(void); +void wwdt_counter_set(uint8_t wwdt_cnt); +void wwdt_window_counter_set(uint8_t window_cnt); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h new file mode 100644 index 0000000000..462594d903 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h @@ -0,0 +1,1075 @@ +/** + ************************************************************************** + * @file at32f435_437_xmc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 xmc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_XMC_H +#define __AT32F435_437_XMC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup XMC + * @{ + */ + +/** @defgroup XMC_exported_types + * @{ + */ + +/** + * @brief xmc data address bus multiplexing type + */ +typedef enum +{ + XMC_DATA_ADDR_MUX_DISABLE = 0x00000000, /*!< xmc address/data multiplexing disable */ + XMC_DATA_ADDR_MUX_ENABLE = 0x00000002 /*!< xmc address/data multiplexing enable */ +} xmc_data_addr_mux_type; + +/** + * @brief xmc burst access mode type + */ +typedef enum +{ + XMC_BURST_MODE_DISABLE = 0x00000000, /*!< xmc burst mode disable */ + XMC_BURST_MODE_ENABLE = 0x00000100 /*!< xmc burst mode enable */ +} xmc_burst_access_mode_type; + +/** + * @brief xmc asynchronous wait type + */ +typedef enum +{ + XMC_ASYN_WAIT_DISABLE = 0x00000000, /*!< xmc wait signal during asynchronous transfers disbale */ + XMC_ASYN_WAIT_ENABLE = 0x00008000 /*!< xmc wait signal during asynchronous transfers enable */ +} xmc_asyn_wait_type; + +/** + * @brief xmc wrapped mode type + */ +typedef enum +{ + XMC_WRAPPED_MODE_DISABLE = 0x00000000, /*!< xmc direct wrapped burst is disbale */ + XMC_WRAPPED_MODE_ENABLE = 0x00000400 /*!< xmc direct wrapped burst is enable */ +} xmc_wrap_mode_type; + +/** + * @brief xmc write operation type + */ +typedef enum +{ + XMC_WRITE_OPERATION_DISABLE = 0x00000000, /*!< xmc write operations is disable */ + XMC_WRITE_OPERATION_ENABLE = 0x00001000 /*!< xmc write operations is enable */ +} xmc_write_operation_type; + +/** + * @brief xmc wait signal type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_DISABLE = 0x00000000, /*!< xmc nwait signal is disable */ + XMC_WAIT_SIGNAL_ENABLE = 0x00002000 /*!< xmc nwait signal is enable */ +} xmc_wait_signal_type; + +/** + * @brief xmc write burst type + */ +typedef enum +{ + XMC_WRITE_BURST_SYN_DISABLE = 0x00000000, /*!< xmc write operations are always performed in asynchronous mode */ + XMC_WRITE_BURST_SYN_ENABLE = 0x00080000 /*!< xmc write operations are performed in synchronous mode */ +} xmc_write_burst_type; + +/** + * @brief xmc extended mode type + */ +typedef enum +{ + XMC_WRITE_TIMING_DISABLE = 0x00000000, /*!< xmc write timing disable */ + XMC_WRITE_TIMING_ENABLE = 0x00004000 /*!< xmc write timing enable */ +} xmc_extended_mode_type; + +/** + * @brief xmc pccard wait type + */ +typedef enum +{ + XMC_WAIT_OPERATION_DISABLE = 0x00000000, /*!< xmc wait operation for the pc card/nand flash memory bank disable */ + XMC_WAIT_OPERATION_ENABLE = 0x00000002 /*!< xmc wait operation for the pc card/nand flash memory bank enable */ +} xmc_nand_pccard_wait_type; + +/** + * @brief xmc ecc enable type + */ +typedef enum +{ + XMC_ECC_OPERATION_DISABLE = 0x00000000, /*!< xmc ecc module disable */ + XMC_ECC_OPERATION_ENABLE = 0x00000040 /*!< xmc ecc module enable */ +} xmc_ecc_enable_type; + +/** + * @brief xmc nor/sram subbank type + */ +typedef enum +{ + XMC_BANK1_NOR_SRAM1 = 0x00000000, /*!< xmc nor/sram subbank1 */ + XMC_BANK1_NOR_SRAM2 = 0x00000001, /*!< xmc nor/sram subbank2 */ + XMC_BANK1_NOR_SRAM3 = 0x00000002, /*!< xmc nor/sram subbank3 */ + XMC_BANK1_NOR_SRAM4 = 0x00000003 /*!< xmc nor/sram subbank4 */ +} xmc_nor_sram_subbank_type; + +/** + * @brief xmc class bank type + */ +typedef enum +{ + XMC_BANK2_NAND = 0x00000000, /*!< xmc nand flash bank2 */ + XMC_BANK3_NAND = 0x00000001, /*!< xmc nand flash bank3 */ + XMC_BANK4_PCCARD = 0x00000002, /*!< xmc pc card bank4 */ + XMC_BANK5_6_SDRAM = 0x00000003 /*!< xmc sdram bank5/6 */ +} xmc_class_bank_type; + +/** + * @brief xmc memory type + */ +typedef enum +{ + XMC_DEVICE_SRAM = 0x00000000, /*!< xmc device choice sram */ + XMC_DEVICE_PSRAM = 0x00000004, /*!< xmc device choice psram */ + XMC_DEVICE_NOR = 0x00000008 /*!< xmc device choice nor flash */ +} xmc_memory_type; + +/** + * @brief xmc data width type + */ +typedef enum +{ + XMC_BUSTYPE_8_BITS = 0x00000000, /*!< xmc databuss width 8bits */ + XMC_BUSTYPE_16_BITS = 0x00000010 /*!< xmc databuss width 16bits */ +} xmc_data_width_type; + +/** + * @brief xmc wait signal polarity type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_LEVEL_LOW = 0x00000000, /*!< xmc nwait active low */ + XMC_WAIT_SIGNAL_LEVEL_HIGH = 0x00000200 /*!< xmc nwait active high */ +} xmc_wait_signal_polarity_type; + +/** + * @brief xmc wait timing type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_SYN_BEFORE = 0x00000000, /*!< xmc nwait signal is active one data cycle before wait state */ + XMC_WAIT_SIGNAL_SYN_DURING = 0x00000800 /*!< xmc nwait signal is active during wait state */ +} xmc_wait_timing_type; + +/** + * @brief xmc access mode type + */ +typedef enum +{ + XMC_ACCESS_MODE_A = 0x00000000, /*!< xmc access mode A */ + XMC_ACCESS_MODE_B = 0x10000000, /*!< xmc access mode B */ + XMC_ACCESS_MODE_C = 0x20000000, /*!< xmc access mode C */ + XMC_ACCESS_MODE_D = 0x30000000 /*!< xmc access mode D */ +} xmc_access_mode_type; + +/** + * @brief xmc ecc page size type + */ +typedef enum +{ + XMC_ECC_PAGESIZE_256_BYTES = 0x00000000, /*!< xmc ecc page size 256 bytes */ + XMC_ECC_PAGESIZE_512_BYTES = 0x00020000, /*!< xmc ecc page size 512 bytes */ + XMC_ECC_PAGESIZE_1024_BYTES = 0x00040000, /*!< xmc ecc page size 1024 bytes */ + XMC_ECC_PAGESIZE_2048_BYTES = 0x00060000, /*!< xmc ecc page size 2048 bytes */ + XMC_ECC_PAGESIZE_4096_BYTES = 0x00080000, /*!< xmc ecc page size 4096 bytes */ + XMC_ECC_PAGESIZE_8192_BYTES = 0x000A0000 /*!< xmc ecc page size 8192 bytes */ +} xmc_ecc_pagesize_type; + +/** + * @brief xmc interrupt sources type + */ +typedef enum +{ + XMC_INT_RISING_EDGE = 0x00000008, /*!< xmc rising edge detection interrupt enable */ + XMC_INT_LEVEL = 0x00000010, /*!< xmc high-level edge detection interrupt enable */ + XMC_INT_FALLING_EDGE = 0x00000020, /*!< xmc falling edge detection interrupt enable */ + XMC_INT_ERR = 0x00004000 /*!< xmc sdram error interrupt enable */ +} xmc_interrupt_sources_type; + +/** + * @brief xmc interrupt flag type + */ +typedef enum +{ + XMC_RISINGEDGE_FLAG = 0x00000001, /*!< xmc interrupt rising edge detection flag */ + XMC_LEVEL_FLAG = 0x00000002, /*!< xmc interrupt high-level edge detection flag */ + XMC_FALLINGEDGE_FLAG = 0x00000004, /*!< xmc interrupt falling edge detection flag */ + XMC_FEMPT_FLAG = 0x00000040, /*!< xmc fifo empty flag */ + XMC_ERR_FLAG = 0x00000001, /*!< xmc sdram error flag */ + XMC_BUSY_FLAG = 0x00000020 /*!< xmc sdram busy flag */ +} xmc_interrupt_flag_type; + +/** + * @brief xmc sdram number of column address type + */ +typedef enum +{ + XMC_COLUMN_8 = 0x00000000, /*!< xmc sdram column address 8bit */ + XMC_COLUMN_9 = 0x00000001, /*!< xmc sdram column address 9bit */ + XMC_COLUMN_10 = 0x00000002, /*!< xmc sdram column address 10bit */ + XMC_COLUMN_11 = 0x00000003 /*!< xmc sdram column address 11bit */ +}xmc_sdram_column_type; + +/** + * @brief xmc sdram number of row address type + */ +typedef enum +{ + XMC_ROW_11 = 0x00000000, /*!< xmc sdram row address 11bit */ + XMC_ROW_12 = 0x00000001, /*!< xmc sdram row address 12bit */ + XMC_ROW_13 = 0x00000002 /*!< xmc sdram row address 13bit */ +}xmc_sdram_row_type; + +/** + * @brief xmc sdram memory data bus width type + */ +typedef enum +{ + XMC_MEM_WIDTH_8 = 0x00000000, /*!< xmc sdram data bus width 8 */ + XMC_MEM_WIDTH_16 = 0x00000001 /*!< xmc sdram data bus width 16 */ +}xmc_sdram_width_type; + +/** + * @brief xmc sdram number of internal banks type + */ +typedef enum +{ + XMC_INBK_2 = 0x00000000, /*!< xmc sdram 2 internal banks */ + XMC_INBK_4 = 0x00000001 /*!< xmc sdram 4 internal banks */ +}xmc_sdram_inbk_type; + +/** + * @brief xmc sdram cas latency type + */ +typedef enum +{ + XMC_CAS_1 = 0x00000001, /*!< xmc sdram cas 1 */ + XMC_CAS_2 = 0x00000002, /*!< xmc sdram cas 2 */ + XMC_CAS_3 = 0x00000003 /*!< xmc sdram cas 3 */ +}xmc_sdram_cas_type; + +/** + * @brief xmc sdram clock div type + */ +typedef enum +{ + XMC_NO_CLK = 0x00000000, /*!< xmc sdram disable clock */ + XMC_CLKDIV_2 = 0x00000002, /*!< xmc sdram clock div 2 */ + XMC_CLKDIV_3 = 0x00000003, /*!< xmc sdram clock div 3 */ + XMC_CLKDIV_4 = 0x00000001 /*!< xmc sdram clock div 4 */ +}xmc_sdram_clkdiv_type; + +/** + * @brief xmc sdram read delay + */ +typedef enum +{ + XMC_READ_DELAY_0 = 0x00000000, /*!< xmc sdram no delay */ + XMC_READ_DELAY_1 = 0x00000001, /*!< xmc sdram delay 1 clock*/ + XMC_READ_DELAY_2 = 0x00000002, /*!< xmc sdram delay 2 clock */ +}xmc_sdram_rd_delay_type; + +/** + * @brief xmc sdram bank type + */ +typedef enum +{ + XMC_SDRAM_BANK1 = 0x00000000, /*!< xmc sdram bank 1 */ + XMC_SDRAM_BANK2 = 0x00000001 /*!< xmc sdram bank 2 */ +}xmc_sdram_bank_type; + + +/** + * @brief xmc sdram timing delay cycle type + */ +typedef enum +{ + XMC_DELAY_CYCLE_1 = 0x00000000, /*!< xmc sdram timming delay 1 cycle */ + XMC_DELAY_CYCLE_2 = 0x00000001, /*!< xmc sdram timming delay 2 cycle */ + XMC_DELAY_CYCLE_3 = 0x00000002, /*!< xmc sdram timming delay 3 cycle */ + XMC_DELAY_CYCLE_4 = 0x00000003, /*!< xmc sdram timming delay 4 cycle */ + XMC_DELAY_CYCLE_5 = 0x00000004, /*!< xmc sdram timming delay 5 cycle */ + XMC_DELAY_CYCLE_6 = 0x00000005, /*!< xmc sdram timming delay 6 cycle */ + XMC_DELAY_CYCLE_7 = 0x00000006, /*!< xmc sdram timming delay 7 cycle */ + XMC_DELAY_CYCLE_8 = 0x00000007, /*!< xmc sdram timming delay 8 cycle */ + XMC_DELAY_CYCLE_9 = 0x00000008, /*!< xmc sdram timming delay 9 cycle */ + XMC_DELAY_CYCLE_10 = 0x00000009, /*!< xmc sdram timming delay 10 cycle */ + XMC_DELAY_CYCLE_11 = 0x0000000A, /*!< xmc sdram timming delay 11 cycle */ + XMC_DELAY_CYCLE_12 = 0x0000000B, /*!< xmc sdram timming delay 12 cycle */ + XMC_DELAY_CYCLE_13 = 0x0000000C, /*!< xmc sdram timming delay 13 cycle */ + XMC_DELAY_CYCLE_14 = 0x0000000D, /*!< xmc sdram timming delay 14 cycle */ + XMC_DELAY_CYCLE_15 = 0x0000000E, /*!< xmc sdram timming delay 15 cycle */ + XMC_DELAY_CYCLE_16 = 0x0000000F /*!< xmc sdram timming delay 16 cycle */ +}xmc_sdram_delay_type; + + +/** + * @brief xmc sdram command type + */ +typedef enum +{ + XMC_CMD_NORMAL = 0x00000000, /*!< xmc sdram command normal */ + XMC_CMD_CLK = 0x00000001, /*!< xmc sdram command clock enable */ + XMC_CMD_PRECHARG_ALL = 0x00000002, /*!< xmc sdram command precharg all bank */ + XMC_CMD_AUTO_REFRESH = 0x00000003, /*!< xmc sdram command auto refresh */ + XMC_CMD_LOAD_MODE = 0x00000004, /*!< xmc sdram command load mode register */ + XMC_CMD_SELF_REFRESH = 0x00000005, /*!< xmc sdram command self refresh */ + XMC_CMD_POWER_DOWN = 0x00000006 /*!< xmc sdram command power down */ +}xmc_command_type; + +/** + * @brief xmc sdram command bank select type + */ +typedef enum +{ + XMC_CMD_BANK1 = 0x00000010, /*!< send xmc sdram command to bank1 */ + XMC_CMD_BANK2 = 0x00000008, /*!< send xmc sdram command to bank2 */ + XMC_CMD_BANK1_2 = 0x00000018 /*!< send xmc sdram command to bank1 and bank2 */ +}xmc_cmd_bank1_2_type; + + +/** + * @brief xmc sdram bank status type + */ +typedef enum +{ + XMC_STATUS_NORMAL = 0x00000000, /*!< xmc sdram status normal */ + XMC_STATUS_SELF_REFRESH = 0x00000001, /*!< xmc sdram status self refresh */ + XMC_STATUS_POWER_DOWN = 0x00000002, /*!< xmc sdram power down */ + XMC_STATUS_MASK = 0x00000003 /*!< xmc sdram mask */ +}xmc_bank_status_type; + + +/** + * @brief nor/sram banks timing parameters + */ +typedef struct +{ + xmc_nor_sram_subbank_type subbank; /*!< xmc nor/sram subbank */ + xmc_extended_mode_type write_timing_enable; /*!< xmc nor/sram write timing enable */ + uint32_t addr_setup_time; /*!< xmc nor/sram address setup time */ + uint32_t addr_hold_time; /*!< xmc nor/sram address hold time */ + uint32_t data_setup_time; /*!< xmc nor/sram data setup time */ + uint32_t bus_latency_time; /*!< xmc nor/sram bus latency time */ + uint32_t clk_psc; /*!< xmc nor/sram clock prescale */ + uint32_t data_latency_time; /*!< xmc nor/sram data latency time */ + xmc_access_mode_type mode; /*!< xmc nor/sram access mode */ +} xmc_norsram_timing_init_type; + +/** + * @brief xmc nor/sram init structure definition + */ +typedef struct +{ + xmc_nor_sram_subbank_type subbank; /*!< xmc nor/sram subbank */ + xmc_data_addr_mux_type data_addr_multiplex; /*!< xmc nor/sram address/data multiplexing enable */ + xmc_memory_type device; /*!< xmc nor/sram memory device */ + xmc_data_width_type bus_type; /*!< xmc nor/sram data bus width */ + xmc_burst_access_mode_type burst_mode_enable; /*!< xmc nor/sram burst mode enable */ + xmc_asyn_wait_type asynwait_enable; /*!< xmc nor/sram nwait in asynchronous transfer enable */ + xmc_wait_signal_polarity_type wait_signal_lv; /*!< xmc nor/sram nwait polarity */ + xmc_wrap_mode_type wrapped_mode_enable; /*!< xmc nor/sram wrapped enable */ + xmc_wait_timing_type wait_signal_config; /*!< xmc nor/sram nwait timing configuration */ + xmc_write_operation_type write_enable; /*!< xmc nor/sram write enable */ + xmc_wait_signal_type wait_signal_enable; /*!< xmc nor/sram nwait in synchronous transfer enable */ + xmc_extended_mode_type write_timing_enable; /*!< xmc nor/sram read-write timing different */ + xmc_write_burst_type write_burst_syn; /*!< xmc nor/sram memory write mode control */ +} xmc_norsram_init_type; + +/** + * @brief nand and pccard timing parameters xmc + */ + +typedef struct +{ + xmc_class_bank_type class_bank; /*!< xmc nand/pccard bank */ + uint32_t mem_setup_time; /*!< xmc nand/pccard memory setup time */ + uint32_t mem_waite_time; /*!< xmc nand/pccard memory wait time */ + uint32_t mem_hold_time; /*!< xmc nand/pccard memory hold time */ + uint32_t mem_hiz_time; /*!< xmc nand/pccard memory databus high resistance time */ +} xmc_nand_pccard_timinginit_type; + +/** + * @brief xmc nand init structure definition + */ + +typedef struct +{ + xmc_class_bank_type nand_bank; /*!< xmc nand bank */ + xmc_nand_pccard_wait_type wait_enable; /*!< xmc wait feature enable */ + xmc_data_width_type bus_type; /*!< xmc nand bus width */ + xmc_ecc_enable_type ecc_enable; /*!< xmc nand ecc enable */ + xmc_ecc_pagesize_type ecc_pagesize; /*!< xmc nand ecc page size */ + uint32_t delay_time_cycle; /*!< xmc nand cle to re delay */ + uint32_t delay_time_ar; /*!< xmc nand ale to re delay */ +} xmc_nand_init_type; + +/** + * @brief xmc pccard init structure definition + */ + +typedef struct +{ + xmc_nand_pccard_wait_type enable_wait; /*!< xmc pccard wait feature enable */ + uint32_t delay_time_cr; /*!< xmc pccard cle to re delay */ + uint32_t delay_time_ar; /*!< xmc pccard ale to re delay */ +} xmc_pccard_init_type; + +/** + * @brief xmc sdram init structure definition + */ + +typedef struct +{ + xmc_sdram_bank_type sdram_bank; /*!< xmc sdram bank bype */ + xmc_sdram_inbk_type internel_banks; /*!< xmc sdram internal banks */ + xmc_sdram_clkdiv_type clkdiv; /*!< xmc sdram clock div */ + uint8_t write_protection; /*!< xmc sdram write protection */ + uint8_t burst_read; /*!< xmc sdram burst read */ + uint8_t read_delay; /*!< xmc sdram read delay */ + xmc_sdram_column_type column_address; /*!< xmc sdram column address */ + xmc_sdram_row_type row_address; /*!< xmc sdram row address */ + xmc_sdram_cas_type cas; /*!< xmc sdram cas */ + xmc_sdram_width_type width; /*!< xmc sdram data width */ +} xmc_sdram_init_type; + +/** + * @brief xmc sdram timing structure definition + */ + +typedef struct +{ + xmc_sdram_delay_type tmrd; /*!< mode register program to active delay */ + xmc_sdram_delay_type txsr; /*!< exit self-refresh to active delay */ + xmc_sdram_delay_type tras; /*!< self refresh */ + xmc_sdram_delay_type trc; /*!< refresh to active delay */ + xmc_sdram_delay_type twr; /*!< write recovery delay */ + xmc_sdram_delay_type trp; /*!< precharge to active delay */ + xmc_sdram_delay_type trcd; /*!< row active to read/write delay */ +} xmc_sdram_timing_type; + +/** + * @brief xmc sdram command structure definition + */ + +typedef struct +{ + xmc_command_type cmd; /*!< sdram command */ + xmc_cmd_bank1_2_type cmd_banks; /*!< which bank send command */ + uint32_t auto_refresh; /*!< auto refresh times */ + uint32_t data; /*!< mode register data */ +} xmc_sdram_cmd_type; + +typedef struct +{ + /** + * @brief xmc bank1 bk1ctrl register, offset:0x00+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1ctrl; + struct + { + __IO uint32_t en : 1; /* [0] */ + __IO uint32_t admuxen : 1; /* [1] */ + __IO uint32_t dev : 2; /* [3:2] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t noren : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t syncben : 1; /* [8] */ + __IO uint32_t nwpol : 1; /* [9] */ + __IO uint32_t wrapen : 1; /* [10] */ + __IO uint32_t nwtcfg : 1; /* [11] */ + __IO uint32_t wen : 1; /* [12] */ + __IO uint32_t nwsen : 1; /* [13] */ + __IO uint32_t rwtd : 1; /* [14] */ + __IO uint32_t nwasen : 1; /* [15] */ + __IO uint32_t crpgs : 3; /* [18:16] */ + __IO uint32_t mwmc : 1; /* [19] */ + __IO uint32_t reserved2 : 12;/* [31:20] */ + } bk1ctrl_bit; + }; + + /** + * @brief xmc bank1 bk1tmg register, offset:0x04+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1tmg; + struct + { + __IO uint32_t addrst : 4; /* [3:0] */ + __IO uint32_t addrht : 4; /* [7:4] */ + __IO uint32_t dtst : 8; /* [15:8] */ + __IO uint32_t buslat : 4; /* [19:16] */ + __IO uint32_t clkpsc : 4; /* [23:20] */ + __IO uint32_t dtlat : 4; /* [27:24] */ + __IO uint32_t asyncm : 2; /* [29:28] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } bk1tmg_bit; + }; + +} xmc_bank1_ctrl_tmg_reg_type; + +typedef struct +{ + /** + * @brief xmc bank1 bk1tmgwr register, offset:0x104+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1tmgwr; + struct + { + __IO uint32_t addrst : 4; /* [3:0] */ + __IO uint32_t addrht : 4; /* [7:4] */ + __IO uint32_t dtst : 8; /* [15:8] */ + __IO uint32_t buslat : 4; /* [19:16] */ + __IO uint32_t reserved1 : 8; /* [27:20] */ + __IO uint32_t asyncm : 2; /* [29:28] */ + __IO uint32_t reserved2 : 2; /* [31:30] */ + } bk1tmgwr_bit; + }; + + /** + * @brief xmc bank1 reserved register + */ + __IO uint32_t reserved1; + +} xmc_bank1_tmgwr_reg_type; + +/** + * @brief xmc bank1 registers + */ +typedef struct +{ + /** + * @brief xmc bank1 ctrl and tmg register, offset:0x00~0x1C + */ + xmc_bank1_ctrl_tmg_reg_type ctrl_tmg_group[4]; + + /** + * @brief xmc bank1 reserved register, offset:0x20~0x100 + */ + __IO uint32_t reserved1[57]; + + /** + * @brief xmc bank1 tmgwr register, offset:0x104~0x11C + */ + xmc_bank1_tmgwr_reg_type tmgwr_group[4]; + + /** + * @brief xmc bank1 reserved register, offset:0x120~0x21C + */ + __IO uint32_t reserved2[63]; + + /** + * @brief xmc bank1 ext register, offset:0x220~0x22C + */ + union + { + __IO uint32_t ext[4]; + struct + { + __IO uint32_t buslatw2w : 8; /* [7:0] */ + __IO uint32_t buslatr2r : 8; /* [15:8] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } ext_bit[4]; + }; + +} xmc_bank1_type; + +/** + * @brief xmc bank2 registers + */ +typedef struct +{ + /** + * @brief xmc bk2ctrl register, offset:0x60 + */ + union + { + __IO uint32_t bk2ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk2ctrl_bit; + }; + + /** + * @brief xmc bk2is register, offset:0x64 + */ + union + { + __IO uint32_t bk2is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk2is_bit; + }; + + /** + * @brief xmc bk2tmgmem register, offset:0x68 + */ + union + { + __IO uint32_t bk2tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk2tmgmem_bit; + }; + + /** + * @brief xmc bk2tmgatt register, offset:0x6C + */ + union + { + __IO uint32_t bk2tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk2tmgatt_bit; + }; + + /** + * @brief xmc reserved register, offset:0x70 + */ + __IO uint32_t reserved1; + + /** + * @brief xmc bk2ecc register, offset:0x74 + */ + union + { + __IO uint32_t bk2ecc; + struct + { + __IO uint32_t ecc : 32; /* [31:0] */ + } bk2ecc_bit; + }; + +} xmc_bank2_type; + +/** + * @brief xmc bank3 registers + */ +typedef struct +{ + /** + * @brief xmc bk3ctrl register, offset:0x80 + */ + union + { + __IO uint32_t bk3ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk3ctrl_bit; + }; + + /** + * @brief xmc bk3is register, offset:0x84 + */ + union + { + __IO uint32_t bk3is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk3is_bit; + }; + + /** + * @brief xmc bk3tmgmem register, offset:0x88 + */ + union + { + __IO uint32_t bk3tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk3tmgmem_bit; + }; + + /** + * @brief xmc bk3tmgatt register, offset:0x8C + */ + union + { + __IO uint32_t bk3tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk3tmgatt_bit; + }; + + /** + * @brief xmc reserved register, offset:0x90 + */ + __IO uint32_t reserved1; + + /** + * @brief xmc bk3ecc register, offset:0x94 + */ + union + { + __IO uint32_t bk3ecc; + struct + { + __IO uint32_t ecc : 32; /* [31:0] */ + } bk3ecc_bit; + }; +} xmc_bank3_type; + +/** + * @brief xmc bank4 registers + */ +typedef struct +{ + + /** + * @brief xmc bk4ctrl register, offset:0xA0 + */ + union + { + __IO uint32_t bk4ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk4ctrl_bit; + }; + + /** + * @brief xmc bk4is register, offset:0xA4 + */ + union + { + __IO uint32_t bk4is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk4is_bit; + }; + + /** + * @brief xmc bk4tmgmem register, offset:0xA8 + */ + union + { + __IO uint32_t bk4tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk4tmgmem_bit; + }; + + /** + * @brief xmc bk4tmgatt register, offset:0xAC + */ + union + { + __IO uint32_t bk4tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk4tmgatt_bit; + }; + + /** + * @brief xmc bk4tmgio register, offset:0xB0 + */ + union + { + __IO uint32_t bk4tmgio; + struct + { + __IO uint32_t iost : 8; /* [7:0] */ + __IO uint32_t iowt : 8; /* [15:8] */ + __IO uint32_t ioht : 8; /* [23:16] */ + __IO uint32_t iohizt : 8; /* [31:24] */ + } bk4tmgio_bit; + }; +} xmc_bank4_type; + +/** + * @brief xmc sdram type + */ +typedef struct +{ + /** + * @brief xmc sdram ctrl register, offset:0x140~0x144 + */ + union + { + __IO uint32_t ctrl[2]; + struct + { + __IO uint32_t ca : 2; /* [1:0] */ + __IO uint32_t ra : 2; /* [3:2] */ + __IO uint32_t db : 2; /* [5:4] */ + __IO uint32_t inbk : 1; /* [6] */ + __IO uint32_t cas : 2; /* [8:7] */ + __IO uint32_t wrp : 1; /* [9] */ + __IO uint32_t clkdiv : 2; /* [11:10] */ + __IO uint32_t bstr : 1; /* [12] */ + __IO uint32_t rd : 2; /* [14:13] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } ctrl_bit[2]; + }; + + /** + * @brief xmc sdram tm register, offset:0x148~0x14C + */ + union + { + __IO uint32_t tm[2]; + struct + { + __IO uint32_t tmrd : 4; /* [3:0] */ + __IO uint32_t txsr : 4; /* [7:4] */ + __IO uint32_t tras : 4; /* [11:8] */ + __IO uint32_t trc : 4; /* [15:12] */ + __IO uint32_t twr : 4; /* [19:16] */ + __IO uint32_t trp : 4; /* [23:20] */ + __IO uint32_t trcd : 4; /* [27:24] */ + __IO uint32_t reserved1 : 4; /* [31:28] */ + } tm_bit[2]; + + }; + +/** + * @brief xmc sdram cmd register, offset:0x150 + */ + union + { + __IO uint32_t cmd; + struct + { + __IO uint32_t cmd : 3; /* [2:0] */ + __IO uint32_t bk2 : 1; /* [3] */ + __IO uint32_t bk1 : 1; /* [4] */ + __IO uint32_t art : 4; /* [8:5] */ + __IO uint32_t mrd : 13;/* [21:9] */ + __IO uint32_t reserved1 : 10;/* [31:22] */ + } cmd_bit; + }; + + /** + * @brief xmc sdram rcnt register, offset:0x154 + */ + union + { + __IO uint32_t rcnt; + struct + { + __IO uint32_t errc : 1; /* [0] */ + __IO uint32_t rc : 13;/* [13:1] */ + __IO uint32_t erien : 1; /* [14] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } rcnt_bit; + }; + + /** + * @brief xmc sdram sts register, offset:0x158 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t err : 1; /* [0] */ + __IO uint32_t bk1sts : 2; /* [2:1] */ + __IO uint32_t bk2sts : 2; /* [4:3] */ + __IO uint32_t busy : 1; /* [5] */ + __IO uint32_t reserved1 : 26;/* [31:6] */ + } sts_bit; + }; +}xmc_sdram_type; + +/** + * @} + */ + +#define XMC_BANK1 ((xmc_bank1_type *) XMC_BANK1_REG_BASE) +#define XMC_BANK2 ((xmc_bank2_type *) XMC_BANK2_REG_BASE) +#define XMC_BANK3 ((xmc_bank3_type *) XMC_BANK3_REG_BASE) +#define XMC_BANK4 ((xmc_bank4_type *) XMC_BANK4_REG_BASE) +#define XMC_SDRAM ((xmc_sdram_type *) XMC_SDRAM_REG_BASE) + +/** @defgroup XMC_exported_functions + * @{ + */ + +void xmc_nor_sram_reset(xmc_nor_sram_subbank_type xmc_subbank); +void xmc_nor_sram_init(xmc_norsram_init_type* xmc_norsram_init_struct); +void xmc_nor_sram_timing_config(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct); +void xmc_norsram_default_para_init(xmc_norsram_init_type* xmc_nor_sram_init_struct); +void xmc_norsram_timing_default_para_init(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct); +void xmc_nor_sram_enable(xmc_nor_sram_subbank_type xmc_subbank, confirm_state new_state); +void xmc_ext_timing_config(xmc_nor_sram_subbank_type xmc_sub_bank, uint16_t w2w_timing, uint16_t r2r_timing); +void xmc_nand_reset(xmc_class_bank_type xmc_bank); +void xmc_nand_init(xmc_nand_init_type* xmc_nand_init_struct); +void xmc_nand_timing_config(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct); +void xmc_nand_default_para_init(xmc_nand_init_type* xmc_nand_init_struct); +void xmc_nand_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct); +void xmc_nand_enable(xmc_class_bank_type xmc_bank, confirm_state new_state); +void xmc_nand_ecc_enable(xmc_class_bank_type xmc_bank, confirm_state new_state); +uint32_t xmc_ecc_get(xmc_class_bank_type xmc_bank); +void xmc_interrupt_enable(xmc_class_bank_type xmc_bank, xmc_interrupt_sources_type xmc_int, confirm_state new_state); +flag_status xmc_flag_status_get(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag); +void xmc_flag_clear(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag); +void xmc_pccard_reset(void); +void xmc_pccard_init(xmc_pccard_init_type* xmc_pccard_init_struct); +void xmc_pccard_timing_config(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct); +void xmc_pccard_default_para_init(xmc_pccard_init_type* xmc_pccard_init_struct); +void xmc_pccard_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct); +void xmc_pccard_enable(confirm_state new_state); +void xmc_sdram_reset(xmc_sdram_bank_type xmc_bank); +void xmc_sdram_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct); +void xmc_sdram_default_para_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct); +void xmc_sdram_cmd(xmc_sdram_cmd_type *xmc_sdram_cmd_struct); +uint32_t xmc_sdram_status_get(xmc_sdram_bank_type xmc_bank); +void xmc_sdram_refresh_counter_set(uint32_t counter); +void xmc_sdram_auto_refresh_set(uint32_t number); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c new file mode 100644 index 0000000000..18afcc3bae --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c @@ -0,0 +1,231 @@ +/** + ************************************************************************** + * @file at32f435_437_acc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the acc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ACC + * @brief ACC driver modules + * @{ + */ + +#ifdef ACC_MODULE_ENABLED + +/** @defgroup ACC_private_functions + * @{ + */ + +/** + * @brief enable or disable the acc calibration mode. + * @param acc_trim: specifies the acc calibration type. + * this parameter can be one of the following values: + * - ACC_CAL_HICKCAL + * - ACC_CAL_HICKTRIM + * @param new_state: specifies the acc calibration to be enabled or disabled.(TRUE or FALSE) + * @retval none + */ +void acc_calibration_mode_enable(uint16_t acc_trim, confirm_state new_state) +{ + if(acc_trim == ACC_CAL_HICKCAL) + { + ACC->ctrl1_bit.entrim = FALSE; + } + else + { + ACC->ctrl1_bit.entrim = TRUE; + } + ACC->ctrl1_bit.calon = new_state; +} + +/** + * @brief store calibration step data in acc's ctrl1 register. + * @param step_value: value to be stored in the acc's ctrl1 register + * @retval none + */ +void acc_step_set(uint8_t step_value) +{ + ACC->ctrl1_bit.step = step_value; +} + +/** + * @brief select sof sourse for acc in acc's ctrl1 register. + * @param sof_sel: value to be stored in the acc's ctrl1 register + * this parameter can be one of the following values: + * @arg ACC_SOF_OTG1 + * @arg ACC_SOF_OTG2 + * @retval none + */ +void acc_sof_select(uint16_t sof_sel) +{ + ACC->ctrl1 |= sof_sel; +} + +/** + * @brief enable or disable the specified acc interrupts. + * @param acc_int: specifies the acc interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - ACC_CALRDYIEN_INT + * - ACC_EIEN_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void acc_interrupt_enable(uint16_t acc_int, confirm_state new_state) +{ + if(acc_int == ACC_CALRDYIEN_INT) + { + ACC->ctrl1_bit.calrdyien = new_state; + } + else + { + ACC->ctrl1_bit.eien = new_state; + } +} + +/** + * @brief return the current acc hicktrim value. + * @param none + * @retval 8-bit hicktrim value. + */ +uint8_t acc_hicktrim_get(void) +{ + return ((uint8_t)(ACC->ctrl2_bit.hicktrim)); +} + +/** + * @brief return the current acc hickcal value. + * @param none + * @retval 8-bit hicktrim value. + */ +uint8_t acc_hickcal_get(void) +{ + return ((uint8_t)(ACC->ctrl2_bit.hickcal)); +} + +/** + * @brief wtire the value to acc c1 register. + * @param acc_c1_value + * @retval none. + */ +void acc_write_c1(uint16_t acc_c1_value) +{ + ACC->c1 = acc_c1_value; +} + +/** + * @brief wtire the value to acc c2 register. + * @param acc_c2_value + * @retval none. + */ +void acc_write_c2(uint16_t acc_c2_value) +{ + ACC->c2 = acc_c2_value; +} + +/** + * @brief wtire the value to acc c3 register. + * @param acc_c3_value + * @retval none. + */ +void acc_write_c3(uint16_t acc_c3_value) +{ + ACC->c3 = acc_c3_value; +} + +/** + * @brief return the current acc c1 value. + * @param none + * @retval 16-bit c1 value. + */ +uint16_t acc_read_c1(void) +{ + return ((uint16_t)(ACC->c1)); +} + +/** + * @brief return the current acc c2 value. + * @param none + * @retval 16-bit c2 value. + */ +uint16_t acc_read_c2(void) +{ + return ((uint16_t)(ACC->c2)); +} + +/** + * @brief return the current acc c3 value. + * @param none + * @retval 16-bit c3 value. + */ +uint16_t acc_read_c3(void) +{ + return ((uint16_t)(ACC->c3)); +} + +/** + * @brief check whether the specified acc flag is set or not. + * @param acc_flag: specifies the flag to check. + * this parameter can be one of the following values: + * - ACC_RSLOST_FLAG + * - ACC_CALRDY_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status acc_flag_get(uint16_t acc_flag) +{ + if(acc_flag == ACC_CALRDY_FLAG) + return (flag_status)(ACC->sts_bit.calrdy); + else + return (flag_status)(ACC->sts_bit.rslost); +} + +/** + * @brief clear the specified acc flag is set or not. + * @param acc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - ACC_RSLOST_FLAG + * - ACC_CALRDY_FLAG + * @retval none + */ +void acc_flag_clear(uint16_t acc_flag) +{ + ACC->sts = ~acc_flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c new file mode 100644 index 0000000000..e0a12df55f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c @@ -0,0 +1,1215 @@ +/** + ************************************************************************** + * @file at32f435_437_adc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the adc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +#ifdef ADC_MODULE_ENABLED + +/** @defgroup ADC_private_functions + * @{ + */ + +/** + * @brief deinitialize the adc peripheral registers to their default reset values. + * @param none + * @retval none + */ +void adc_reset(void) +{ + crm_periph_reset(CRM_ADC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_ADC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of a/d converter. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.adcen = new_state; +} + +/** + * @brief adc base default para init. + * @param sequence_mode: set the state of adc sequence mode. + * this parameter can be:TRUE or FALSE + * @param repeat_mode: set the state of adc repeat conversion mode. + * this parameter can be:TRUE or FALSE + * @param data_align: set the state of adc data alignment. + * this parameter can be one of the following values: + * - ADC_RIGHT_ALIGNMENT + * - ADC_LEFT_ALIGNMENT + * @param ordinary_channel_length: configure the adc ordinary channel sequence length. + * this parameter can be: + * - (0x1~0xf) + * @retval none + */ +void adc_base_default_para_init(adc_base_config_type *adc_base_struct) +{ + adc_base_struct->sequence_mode = FALSE; + adc_base_struct->repeat_mode = FALSE; + adc_base_struct->data_align = ADC_RIGHT_ALIGNMENT; + adc_base_struct->ordinary_channel_length = 1; +} + +/** + * @brief initialize the adc peripheral according to the specified parameters. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param sequence_mode: set the state of adc sequence mode. + * this parameter can be:TRUE or FALSE + * @param repeat_mode: set the state of adc repeat conversion mode. + * this parameter can be:TRUE or FALSE + * @param data_align: set the state of adc data alignment. + * this parameter can be one of the following values: + * - ADC_RIGHT_ALIGNMENT + * - ADC_LEFT_ALIGNMENT + * @param ordinary_channel_length: configure the adc ordinary channel sequence length. + * this parameter can be: + * - (0x1~0xf) + * @retval none + */ +void adc_base_config(adc_type *adc_x, adc_base_config_type *adc_base_struct) +{ + adc_x->ctrl1_bit.sqen = adc_base_struct->sequence_mode; + adc_x->ctrl2_bit.rpen = adc_base_struct->repeat_mode; + adc_x->ctrl2_bit.dtalign = adc_base_struct->data_align; + adc_x->osq1_bit.oclen = adc_base_struct->ordinary_channel_length - 1; +} + +/** + * @brief adc common default para init. + * @param combine_mode: configure the adc combine_mode mode. + * this parameter can be one of the following values: + * - ADC_INDEPENDENT_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE + * @param div: configure the adc division. + * this parameter can be one of the following values: + * - ADC_HCLK_DIV_2 - ADC_HCLK_DIV_3 - ADC_HCLK_DIV_4 - ADC_HCLK_DIV_5 + * - ADC_HCLK_DIV_6 - ADC_HCLK_DIV_7 - ADC_HCLK_DIV_8 - ADC_HCLK_DIV_9 + * - ADC_HCLK_DIV_10 - ADC_HCLK_DIV_11 - ADC_HCLK_DIV_12 - ADC_HCLK_DIV_13 + * - ADC_HCLK_DIV_14 - ADC_HCLK_DIV_15 - ADC_HCLK_DIV_16 - ADC_HCLK_DIV_17 + * @param common_dma_mode: configure the adc common dma mode. + * this parameter can be one of the following values: + * - ADC_COMMON_DMAMODE_DISABLE + * - ADC_COMMON_DMAMODE_1 + * - ADC_COMMON_DMAMODE_2 + * - ADC_COMMON_DMAMODE_3 + * - ADC_COMMON_DMAMODE_4 + * - ADC_COMMON_DMAMODE_5 + * @param common_dma_request_repeat_state: set the adc common dma request repeat state. + * this parameter can be:TRUE or FALSE + * @param sampling_interval: configure the ordinary shifting mode adjacent adc sampling interval. + * this parameter can be one of the following values: + * - ADC_SAMPLING_INTERVAL_5CYCLES - ADC_SAMPLING_INTERVAL_6CYCLES - ADC_SAMPLING_INTERVAL_7CYCLES - ADC_SAMPLING_INTERVAL_8CYCLES + * - ADC_SAMPLING_INTERVAL_9CYCLES - ADC_SAMPLING_INTERVAL_10CYCLES - ADC_SAMPLING_INTERVAL_11CYCLES - ADC_SAMPLING_INTERVAL_12CYCLES + * - ADC_SAMPLING_INTERVAL_13CYCLES - ADC_SAMPLING_INTERVAL_14CYCLES - ADC_SAMPLING_INTERVAL_15CYCLES - ADC_SAMPLING_INTERVAL_16CYCLES + * - ADC_SAMPLING_INTERVAL_17CYCLES - ADC_SAMPLING_INTERVAL_18CYCLES - ADC_SAMPLING_INTERVAL_19CYCLES - ADC_SAMPLING_INTERVAL_20CYCLES + * @param tempervintrv_state: set the adc temperature sensor and vintrv state. + * this parameter can be:TRUE or FALSE + * @param vbat_state: set the adc voltage battery state. + * this parameter can be:TRUE or FALSE + * @retval none + */ +void adc_common_default_para_init(adc_common_config_type *adc_common_struct) +{ + adc_common_struct->combine_mode = ADC_INDEPENDENT_MODE; + adc_common_struct->div = ADC_HCLK_DIV_2; + adc_common_struct->common_dma_mode = ADC_COMMON_DMAMODE_DISABLE; + adc_common_struct->common_dma_request_repeat_state = FALSE; + adc_common_struct->sampling_interval = ADC_SAMPLING_INTERVAL_5CYCLES; + adc_common_struct->tempervintrv_state = FALSE; + adc_common_struct->vbat_state = FALSE; +} + +/** + * @brief adc common default para init. + * @param combine_mode: configure the adc combine_mode mode. + * this parameter can be one of the following values: + * - ADC_INDEPENDENT_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE + * @param div: configure the adc division. + * this parameter can be one of the following values: + * - ADC_HCLK_DIV_2 - ADC_HCLK_DIV_3 - ADC_HCLK_DIV_4 - ADC_HCLK_DIV_5 + * - ADC_HCLK_DIV_6 - ADC_HCLK_DIV_7 - ADC_HCLK_DIV_8 - ADC_HCLK_DIV_9 + * - ADC_HCLK_DIV_10 - ADC_HCLK_DIV_11 - ADC_HCLK_DIV_12 - ADC_HCLK_DIV_13 + * - ADC_HCLK_DIV_14 - ADC_HCLK_DIV_15 - ADC_HCLK_DIV_16 - ADC_HCLK_DIV_17 + * @param common_dma_mode: configure the adc common dma mode. + * this parameter can be one of the following values: + * - ADC_COMMON_DMAMODE_DISABLE + * - ADC_COMMON_DMAMODE_1 + * - ADC_COMMON_DMAMODE_2 + * - ADC_COMMON_DMAMODE_3 + * - ADC_COMMON_DMAMODE_4 + * - ADC_COMMON_DMAMODE_5 + * @param common_dma_request_repeat_state: set the adc common dma request repeat state. + * this parameter can be:TRUE or FALSE + * @param sampling_interval: configure the ordinary shifting mode adjacent adc sampling interval. + * this parameter can be one of the following values: + * - ADC_SAMPLING_INTERVAL_5CYCLES - ADC_SAMPLING_INTERVAL_6CYCLES - ADC_SAMPLING_INTERVAL_7CYCLES - ADC_SAMPLING_INTERVAL_8CYCLES + * - ADC_SAMPLING_INTERVAL_9CYCLES - ADC_SAMPLING_INTERVAL_10CYCLES - ADC_SAMPLING_INTERVAL_11CYCLES - ADC_SAMPLING_INTERVAL_12CYCLES + * - ADC_SAMPLING_INTERVAL_13CYCLES - ADC_SAMPLING_INTERVAL_14CYCLES - ADC_SAMPLING_INTERVAL_15CYCLES - ADC_SAMPLING_INTERVAL_16CYCLES + * - ADC_SAMPLING_INTERVAL_17CYCLES - ADC_SAMPLING_INTERVAL_18CYCLES - ADC_SAMPLING_INTERVAL_19CYCLES - ADC_SAMPLING_INTERVAL_20CYCLES + * @param tempervintrv_state: set the adc temperature sensor and vintrv state. + * this parameter can be:TRUE or FALSE + * @param vbat_state: set the adc voltage battery state. + * this parameter can be:TRUE or FALSE + * @retval none + */ +void adc_common_config(adc_common_config_type *adc_common_struct) +{ + ADCCOM->cctrl_bit.mssel = adc_common_struct->combine_mode; + ADCCOM->cctrl_bit.adcdiv = adc_common_struct->div; + if(adc_common_struct->common_dma_mode & 0x04) + { + ADCCOM->cctrl_bit.msdmasel_h = TRUE; + } + else + { + ADCCOM->cctrl_bit.msdmasel_h = FALSE; + } + ADCCOM->cctrl_bit.msdmasel_l = adc_common_struct->common_dma_mode &0x03; + ADCCOM->cctrl_bit.msdrcen = adc_common_struct->common_dma_request_repeat_state; + ADCCOM->cctrl_bit.asisel = adc_common_struct->sampling_interval; + ADCCOM->cctrl_bit.itsrven = adc_common_struct->tempervintrv_state; + ADCCOM->cctrl_bit.vbaten = adc_common_struct->vbat_state; +} + +/** + * @brief set resolution of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param resolution: set the conversion resolution. + * this parameter can be one of the following values: + * - ADC_RESOLUTION_12B + * - ADC_RESOLUTION_10B + * - ADC_RESOLUTION_8B + * - ADC_RESOLUTION_6B + * @retval none + */ +void adc_resolution_set(adc_type *adc_x, adc_resolution_type resolution) +{ + adc_x->ctrl1_bit.crsel = resolution; +} + +/** + * @brief enable or disable the adc voltage battery. + * @param new_state: new state of the adc voltage battery. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_voltage_battery_enable(confirm_state new_state) +{ + ADCCOM->cctrl_bit.vbaten = new_state; +} + +/** + * @brief enable or disable the adc dma transfer. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of the adc dma transfer. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_dma_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocdmaen = new_state; +} + +/** + * @brief enable or disable the adc dma request repeat. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: the adc dma request repeat state. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_dma_request_repeat_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocdrcen = new_state; +} + +/** + * @brief enable or disable the specified adc interrupts. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_int: specifies the adc interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - ADC_OCCE_INT + * - ADC_VMOR_INT + * - ADC_PCCE_INT + * - ADC_OCCO_INT + * @param new_state: new state of the specified adc interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_interrupt_enable(adc_type *adc_x, uint32_t adc_int, confirm_state new_state) +{ + if(new_state == TRUE) + { + adc_x->ctrl1 |= adc_int; + } + else if(new_state == FALSE) + { + adc_x->ctrl1 &= ~adc_int; + } +} + +/** + * @brief set calibration value of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_calibration_value: calibration value of adc. + * this parameter can be: + * - (0x00~0x7F) + * @retval none + */ +void adc_calibration_value_set(adc_type *adc_x, uint8_t adc_calibration_value) +{ + adc_x->calval = adc_calibration_value; +} + +/** + * @brief initialize calibration register of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_calibration_init(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adcalinit = TRUE; +} + +/** + * @brief get calibration register's initialize status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of reset calibration register status(SET or RESET). + */ +flag_status adc_calibration_init_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adcalinit) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief start calibration process of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_calibration_start(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adcal = TRUE; +} + +/** + * @brief get calibration status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of calibration status(SET or RESET). + */ +flag_status adc_calibration_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adcal) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable the voltage monitoring on single/all ordinary or preempt channels of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_voltage_monitoring: choose the adc_voltage_monitoring config. + * this parameter can be one of the following values: + * - ADC_VMONITOR_SINGLE_ORDINARY + * - ADC_VMONITOR_SINGLE_PREEMPT + * - ADC_VMONITOR_SINGLE_ORDINARY_PREEMPT + * - ADC_VMONITOR_ALL_ORDINARY + * - ADC_VMONITOR_ALL_PREEMPT + * - ADC_VMONITOR_ALL_ORDINARY_PREEMPT + * - ADC_VMONITOR_NONE + * @retval none + */ +void adc_voltage_monitor_enable(adc_type *adc_x, adc_voltage_monitoring_type adc_voltage_monitoring) +{ + adc_x->ctrl1_bit.ocvmen = FALSE; + adc_x->ctrl1_bit.pcvmen = FALSE; + adc_x->ctrl1_bit.vmsgen = FALSE; + adc_x->ctrl1 |= adc_voltage_monitoring; +} + +/** + * @brief set voltage monitoring's high and low thresholds value of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_high_threshold: voltage monitoring's high thresholds value. + * this parameter can be: + * - (0x000~0xFFF) + * @param adc_low_threshold: voltage monitoring's low thresholds value. + * this parameter can be: + * - (0x000~0xFFF) + * @retval none + */ +void adc_voltage_monitor_threshold_value_set(adc_type *adc_x, uint16_t adc_high_threshold, uint16_t adc_low_threshold) +{ + adc_x->vmhb_bit.vmhb = adc_high_threshold; + adc_x->vmlb_bit.vmlb = adc_low_threshold; +} + +/** + * @brief select the voltage monitoring's channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @retval none + */ +void adc_voltage_monitor_single_channel_select(adc_type *adc_x, adc_channel_select_type adc_channel) +{ + adc_x->ctrl1_bit.vmcsel = adc_channel; +} + +/** + * @brief set ordinary channel's corresponding rank in the sequencer and sample time of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @param adc_sequence: set rank in the ordinary group sequencer. + * this parameter must be: + * - between 1 to 16 + * @param adc_sampletime: set the sampletime of adc channel. + * this parameter can be one of the following values: + * - ADC_SAMPLETIME_2_5 + * - ADC_SAMPLETIME_6_5 + * - ADC_SAMPLETIME_12_5 + * - ADC_SAMPLETIME_24_5 + * - ADC_SAMPLETIME_47_5 + * - ADC_SAMPLETIME_92_5 + * - ADC_SAMPLETIME_247_5 + * - ADC_SAMPLETIME_640_5 + * @retval none + */ +void adc_ordinary_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime) +{ + switch(adc_channel) + { + case ADC_CHANNEL_0: + adc_x->spt2_bit.cspt0 = adc_sampletime; + break; + case ADC_CHANNEL_1: + adc_x->spt2_bit.cspt1 = adc_sampletime; + break; + case ADC_CHANNEL_2: + adc_x->spt2_bit.cspt2 = adc_sampletime; + break; + case ADC_CHANNEL_3: + adc_x->spt2_bit.cspt3 = adc_sampletime; + break; + case ADC_CHANNEL_4: + adc_x->spt2_bit.cspt4 = adc_sampletime; + break; + case ADC_CHANNEL_5: + adc_x->spt2_bit.cspt5 = adc_sampletime; + break; + case ADC_CHANNEL_6: + adc_x->spt2_bit.cspt6 = adc_sampletime; + break; + case ADC_CHANNEL_7: + adc_x->spt2_bit.cspt7 = adc_sampletime; + break; + case ADC_CHANNEL_8: + adc_x->spt2_bit.cspt8 = adc_sampletime; + break; + case ADC_CHANNEL_9: + adc_x->spt2_bit.cspt9 = adc_sampletime; + break; + case ADC_CHANNEL_10: + adc_x->spt1_bit.cspt10 = adc_sampletime; + break; + case ADC_CHANNEL_11: + adc_x->spt1_bit.cspt11 = adc_sampletime; + break; + case ADC_CHANNEL_12: + adc_x->spt1_bit.cspt12 = adc_sampletime; + break; + case ADC_CHANNEL_13: + adc_x->spt1_bit.cspt13 = adc_sampletime; + break; + case ADC_CHANNEL_14: + adc_x->spt1_bit.cspt14 = adc_sampletime; + break; + case ADC_CHANNEL_15: + adc_x->spt1_bit.cspt15 = adc_sampletime; + break; + case ADC_CHANNEL_16: + adc_x->spt1_bit.cspt16 = adc_sampletime; + break; + case ADC_CHANNEL_17: + adc_x->spt1_bit.cspt17 = adc_sampletime; + break; + case ADC_CHANNEL_18: + adc_x->spt1_bit.cspt18 = adc_sampletime; + break; + default: + break; + } + switch(adc_sequence) + { + case 1: + adc_x->osq3_bit.osn1 = adc_channel; + break; + case 2: + adc_x->osq3_bit.osn2 = adc_channel; + break; + case 3: + adc_x->osq3_bit.osn3 = adc_channel; + break; + case 4: + adc_x->osq3_bit.osn4 = adc_channel; + break; + case 5: + adc_x->osq3_bit.osn5 = adc_channel; + break; + case 6: + adc_x->osq3_bit.osn6 = adc_channel; + break; + case 7: + adc_x->osq2_bit.osn7 = adc_channel; + break; + case 8: + adc_x->osq2_bit.osn8 = adc_channel; + break; + case 9: + adc_x->osq2_bit.osn9 = adc_channel; + break; + case 10: + adc_x->osq2_bit.osn10 = adc_channel; + break; + case 11: + adc_x->osq2_bit.osn11 = adc_channel; + break; + case 12: + adc_x->osq2_bit.osn12 = adc_channel; + break; + case 13: + adc_x->osq1_bit.osn13 = adc_channel; + break; + case 14: + adc_x->osq1_bit.osn14 = adc_channel; + break; + case 15: + adc_x->osq1_bit.osn15 = adc_channel; + break; + case 16: + adc_x->osq1_bit.osn16 = adc_channel; + break; + default: + break; + } +} + +/** + * @brief set preempt channel lenghth of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel_lenght: set the adc preempt channel lenghth. + * this parameter can be: + * - (0x1~0x4) + * @retval none + */ +void adc_preempt_channel_length_set(adc_type *adc_x, uint8_t adc_channel_lenght) +{ + adc_x->psq_bit.pclen = adc_channel_lenght - 1; +} + +/** + * @brief configure preempt channel's corresponding rank in the sequencer and sample time of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @param adc_sequence: set rank in the preempt group sequencer. + * this parameter must be: + * - between 1 to 4 + * @param adc_sampletime: config the sampletime of adc channel. + * this parameter can be one of the following values: + * - ADC_SAMPLETIME_2_5 + * - ADC_SAMPLETIME_6_5 + * - ADC_SAMPLETIME_12_5 + * - ADC_SAMPLETIME_24_5 + * - ADC_SAMPLETIME_47_5 + * - ADC_SAMPLETIME_92_5 + * - ADC_SAMPLETIME_247_5 + * - ADC_SAMPLETIME_640_5 + * @retval none + */ +void adc_preempt_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime) +{ + uint16_t sequence_index=0; + switch(adc_channel) + { + case ADC_CHANNEL_0: + adc_x->spt2_bit.cspt0 = adc_sampletime; + break; + case ADC_CHANNEL_1: + adc_x->spt2_bit.cspt1 = adc_sampletime; + break; + case ADC_CHANNEL_2: + adc_x->spt2_bit.cspt2 = adc_sampletime; + break; + case ADC_CHANNEL_3: + adc_x->spt2_bit.cspt3 = adc_sampletime; + break; + case ADC_CHANNEL_4: + adc_x->spt2_bit.cspt4 = adc_sampletime; + break; + case ADC_CHANNEL_5: + adc_x->spt2_bit.cspt5 = adc_sampletime; + break; + case ADC_CHANNEL_6: + adc_x->spt2_bit.cspt6 = adc_sampletime; + break; + case ADC_CHANNEL_7: + adc_x->spt2_bit.cspt7 = adc_sampletime; + break; + case ADC_CHANNEL_8: + adc_x->spt2_bit.cspt8 = adc_sampletime; + break; + case ADC_CHANNEL_9: + adc_x->spt2_bit.cspt9 = adc_sampletime; + break; + case ADC_CHANNEL_10: + adc_x->spt1_bit.cspt10 = adc_sampletime; + break; + case ADC_CHANNEL_11: + adc_x->spt1_bit.cspt11 = adc_sampletime; + break; + case ADC_CHANNEL_12: + adc_x->spt1_bit.cspt12 = adc_sampletime; + break; + case ADC_CHANNEL_13: + adc_x->spt1_bit.cspt13 = adc_sampletime; + break; + case ADC_CHANNEL_14: + adc_x->spt1_bit.cspt14 = adc_sampletime; + break; + case ADC_CHANNEL_15: + adc_x->spt1_bit.cspt15 = adc_sampletime; + break; + case ADC_CHANNEL_16: + adc_x->spt1_bit.cspt16 = adc_sampletime; + break; + case ADC_CHANNEL_17: + adc_x->spt1_bit.cspt17 = adc_sampletime; + break; + case ADC_CHANNEL_18: + adc_x->spt1_bit.cspt18 = adc_sampletime; + break; + default: + break; + } + sequence_index = adc_sequence + 3 - adc_x->psq_bit.pclen; + switch(sequence_index) + { + case 1: + adc_x->psq_bit.psn1 = adc_channel; + break; + case 2: + adc_x->psq_bit.psn2 = adc_channel; + break; + case 3: + adc_x->psq_bit.psn3 = adc_channel; + break; + case 4: + adc_x->psq_bit.psn4 = adc_channel; + break; + default: + break; + } +} + +/** + * @brief set the ordinary channel's external trigger edge and + * set external trigger event of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_ordinary_trig: select the external trigger event. + * this parameter can be one of the following values: + * - ADC_ORDINARY_TRIG_TMR1CH1 - ADC_ORDINARY_TRIG_TMR1CH2 - ADC_ORDINARY_TRIG_TMR1CH3 - ADC_ORDINARY_TRIG_TMR2CH2 + * - ADC_ORDINARY_TRIG_TMR2CH3 - ADC_ORDINARY_TRIG_TMR2CH4 - ADC_ORDINARY_TRIG_TMR2TRGOUT - ADC_ORDINARY_TRIG_TMR3CH1 + * - ADC_ORDINARY_TRIG_TMR3TRGOUT - ADC_ORDINARY_TRIG_TMR4CH4 - ADC_ORDINARY_TRIG_TMR5CH1 - ADC_ORDINARY_TRIG_TMR5CH2 + * - ADC_ORDINARY_TRIG_TMR5CH3 - ADC_ORDINARY_TRIG_TMR8CH1 - ADC_ORDINARY_TRIG_TMR8TRGOUT - ADC_ORDINARY_TRIG_EXINT11 + * - ADC_ORDINARY_TRIG_TMR20TRGOUT - ADC_ORDINARY_TRIG_TMR20TRGOUT2 - ADC_ORDINARY_TRIG_TMR20CH1 - ADC_ORDINARY_TRIG_TMR20CH2 + * - ADC_ORDINARY_TRIG_TMR20CH3 - ADC_ORDINARY_TRIG_TMR8TRGOUT2 - ADC_ORDINARY_TRIG_TMR1TRGOUT2 - ADC_ORDINARY_TRIG_TMR4TRGOUT + * - ADC_ORDINARY_TRIG_TMR6TRGOUT - ADC_ORDINARY_TRIG_TMR3CH4 - ADC_ORDINARY_TRIG_TMR4CH1 - ADC_ORDINARY_TRIG_TMR1TRGOUT + * - ADC_ORDINARY_TRIG_TMR2CH1 - ADC_ORDINARY_TRIG_TMR7TRGOUT + * @param adc_ordinary_trig_edge: ordinary channel conversion's external_trigger_edge. + * this parameter can be one of the following values: + * - ADC_ORDINARY_TRIG_EDGE_NONE + * - ADC_ORDINARY_TRIG_EDGE_RISING + * - ADC_ORDINARY_TRIG_EDGE_FALLING + * - ADC_ORDINARY_TRIG_EDGE_RISING_FALLING + * @retval none + */ +void adc_ordinary_conversion_trigger_set(adc_type *adc_x, adc_ordinary_trig_select_type adc_ordinary_trig, adc_ordinary_trig_edge_type adc_ordinary_trig_edge) +{ + if(adc_ordinary_trig > ADC_ORDINARY_TRIG_EXINT11) + { + adc_x->ctrl2_bit.octesel_h = 1; + adc_x->ctrl2_bit.octesel_l = adc_ordinary_trig & 0x0F; + } + else + { + adc_x->ctrl2_bit.octesel_h = 0; + adc_x->ctrl2_bit.octesel_l = adc_ordinary_trig & 0x0F; + } + adc_x->ctrl2_bit.ocete = adc_ordinary_trig_edge; +} + +/** + * @brief enable or disable the preempt channel's external trigger and + * set external trigger event of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_trig: select the external trigger event. + * this parameter can be one of the following values: + * - ADC_PREEMPT_TRIG_TMR1CH4 - ADC_PREEMPT_TRIG_TMR1TRGOUT - ADC_PREEMPT_TRIG_TMR2CH1 - ADC_PREEMPT_TRIG_TMR2TRGOUT + * - ADC_PREEMPT_TRIG_TMR3CH2 - ADC_PREEMPT_TRIG_TMR3CH4 - ADC_PREEMPT_TRIG_TMR4CH1 - ADC_PREEMPT_TRIG_TMR4CH2 + * - ADC_PREEMPT_TRIG_TMR4CH3 - ADC_PREEMPT_TRIG_TMR4TRGOUT - ADC_PREEMPT_TRIG_TMR5CH4 - ADC_PREEMPT_TRIG_TMR5TRGOUT + * - ADC_PREEMPT_TRIG_TMR8CH2 - ADC_PREEMPT_TRIG_TMR8CH3 - ADC_PREEMPT_TRIG_TMR8CH4 - ADC_PREEMPT_TRIG_EXINT15 + * - ADC_PREEMPT_TRIG_TMR20TRGOUT - ADC_PREEMPT_TRIG_TMR20TRGOUT2 - ADC_PREEMPT_TRIG_TMR20CH4 - ADC_PREEMPT_TRIG_TMR1TRGOUT2 + * - ADC_PREEMPT_TRIG_TMR8TRGOUT - ADC_PREEMPT_TRIG_TMR8TRGOUT2 - ADC_PREEMPT_TRIG_TMR3CH3 - ADC_PREEMPT_TRIG_TMR3TRGOUT + * - ADC_PREEMPT_TRIG_TMR3CH1 - ADC_PREEMPT_TRIG_TMR6TRGOUT - ADC_PREEMPT_TRIG_TMR4CH4 - ADC_PREEMPT_TRIG_TMR1CH3 + * - ADC_PREEMPT_TRIG_TMR20CH2 - ADC_PREEMPT_TRIG_TMR7TRGOUT + * @param adc_preempt_trig_edge: preempt channel conversion's external_trigger_edge. + * this parameter can be one of the following values: + * - ADC_PREEMPT_TRIG_EDGE_NONE + * - ADC_PREEMPT_TRIG_EDGE_RISING + * - ADC_PREEMPT_TRIG_EDGE_FALLING + * - ADC_PREEMPT_TRIG_EDGE_RISING_FALLING + * @retval none + */ +void adc_preempt_conversion_trigger_set(adc_type *adc_x, adc_preempt_trig_select_type adc_preempt_trig, adc_preempt_trig_edge_type adc_preempt_trig_edge) +{ + if(adc_preempt_trig > ADC_PREEMPT_TRIG_EXINT15) + { + adc_x->ctrl2_bit.pctesel_h = 1; + adc_x->ctrl2_bit.pctesel_l = adc_preempt_trig & 0x0F; + } + else + { + adc_x->ctrl2_bit.pctesel_h = 0; + adc_x->ctrl2_bit.pctesel_l = adc_preempt_trig & 0x0F; + } + adc_x->ctrl2_bit.pcete = adc_preempt_trig_edge; +} + +/** + * @brief set preempt channel's conversion value offset of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_channel: select the preempt channel. + * this parameter can be one of the following values: + * - ADC_PREEMPT_CHANNEL_1 + * - ADC_PREEMPT_CHANNEL_2 + * - ADC_PREEMPT_CHANNEL_3 + * - ADC_PREEMPT_CHANNEL_4 + * @param adc_offset_value: set the adc preempt channel's conversion value offset. + * this parameter can be: + * - (0x000~0xFFF) + * @retval none + */ +void adc_preempt_offset_value_set(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel, uint16_t adc_offset_value) +{ + switch(adc_preempt_channel) + { + case ADC_PREEMPT_CHANNEL_1: + adc_x->pcdto1_bit.pcdto1 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_2: + adc_x->pcdto2_bit.pcdto2 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_3: + adc_x->pcdto3_bit.pcdto3 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_4: + adc_x->pcdto4_bit.pcdto4 = adc_offset_value; + break; + default: + break; + } +} + +/** + * @brief set partitioned mode channel count of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel_count: configure the adc partitioned mode channel count. + * this parameter can be: + * - (0x1~0x8) + * @retval none + */ +void adc_ordinary_part_count_set(adc_type *adc_x, uint8_t adc_channel_count) +{ + + adc_x->ctrl1_bit.ocpcnt = adc_channel_count - 1; +} + +/** + * @brief enable or disable the partitioned mode on ordinary channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary channel's partitioned mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_part_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.ocpen = new_state; +} + +/** + * @brief enable or disable the partitioned mode on preempt channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt channel's partitioned mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_part_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.pcpen = new_state; +} + +/** + * @brief enable or disable automatic preempt group conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of automatic preempt group conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_auto_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.pcautoen = new_state; +} + +/** + * @brief stop the ongoing conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_conversion_stop(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adabrt = TRUE; +} + +/** + * @brief get stop conversion's status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of stop conversion's status(SET or RESET). + */ +flag_status adc_conversion_stop_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adabrt) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable each ordinary channel conversion set occe flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of each ordinary channel conversion set occe flag. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_occe_each_conversion_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.eocsfen = new_state; +} + +/** + * @brief enable or disable ordinary software start conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary software start conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_software_trigger_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocswtrg = new_state; +} + +/** + * @brief get ordinary software start conversion status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of ordinary software start conversion status(SET or RESET). + */ +flag_status adc_ordinary_software_trigger_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.ocswtrg) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable preempt software start conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt software start conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_software_trigger_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.pcswtrg = new_state; +} + +/** + * @brief get preempt software start conversion status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of preempt software start conversion status(SET or RESET). + */ +flag_status adc_preempt_software_trigger_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.pcswtrg) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief return the last conversion data for ordinary channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the last conversion data for ordinary channel. + */ +uint16_t adc_ordinary_conversion_data_get(adc_type *adc_x) +{ + return (uint16_t)(adc_x->odt_bit.odt); +} + +/** + * @brief return the last ordinary conversion data of combine adc. + * @retval the last conversion data for ordinary channel. + */ +uint32_t adc_combine_ordinary_conversion_data_get(void) +{ + return (uint32_t)(ADCCOM->codt); +} + +/** + * @brief return the conversion data for selection preempt channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_channel: select the preempt channel. + * this parameter can be one of the following values: + * - ADC_PREEMPT_CHANNEL_1 + * - ADC_PREEMPT_CHANNEL_2 + * - ADC_PREEMPT_CHANNEL_3 + * - ADC_PREEMPT_CHANNEL_4 + * @retval the conversion data for selection preempt channel. + */ +uint16_t adc_preempt_conversion_data_get(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel) +{ + uint16_t preempt_conv_data_index = 0; + switch(adc_preempt_channel) + { + case ADC_PREEMPT_CHANNEL_1: + preempt_conv_data_index = (uint16_t)(adc_x->pdt1_bit.pdt1); + break; + case ADC_PREEMPT_CHANNEL_2: + preempt_conv_data_index = (uint16_t)(adc_x->pdt2_bit.pdt2); + break; + case ADC_PREEMPT_CHANNEL_3: + preempt_conv_data_index = (uint16_t)(adc_x->pdt3_bit.pdt3); + break; + case ADC_PREEMPT_CHANNEL_4: + preempt_conv_data_index = (uint16_t)(adc_x->pdt4_bit.pdt4); + break; + default: + break; + } + return preempt_conv_data_index; +} + +/** + * @brief get flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_flag: select the adc flag. + * this parameter can be one of the following values: + * - ADC_VMOR_FLAG + * - ADC_OCCE_FLAG + * - ADC_PCCE_FLAG + * - ADC_PCCS_FLAG(no interrupt associated) + * - ADC_OCCS_FLAG(no interrupt associated) + * - ADC_OCCO_FLAG + * - ADC_RDY_FLAG(no interrupt associated) + * @retval the new state of adc flag status(SET or RESET). + */ +flag_status adc_flag_get(adc_type *adc_x, uint8_t adc_flag) +{ + flag_status status = RESET; + + if((adc_x->sts & adc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief clear flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * ADC1, ADC2, ADC3. + * @param adc_flag: select the adc flag. + * this parameter can be any combination of the following values: + * - ADC_VMOR_FLAG + * - ADC_OCCE_FLAG(also can clear by reading the adc_x->odt) + * - ADC_PCCE_FLAG + * - ADC_PCCS_FLAG + * - ADC_OCCS_FLAG + * - ADC_OCCO_FLAG + * - note:"ADC_RDY_FLAG" cannot be choose!rdy bit is readonly bit,it means the adc is ready to accept conversion request + * @retval none + */ +void adc_flag_clear(adc_type *adc_x, uint32_t adc_flag) +{ + adc_x->sts = ~adc_flag; +} + +/** + * @brief enable or disable the ordinary oversampling of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary oversampling. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_oversample_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.oosen = new_state; +} + +/** + * @brief enable or disable the preempt oversampling of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt oversampling. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_oversample_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.posen = new_state; +} + +/** + * @brief config the oversampling ratio and shift of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_oversample_ratio: set the oversample ratio. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_RATIO_2 + * - ADC_OVERSAMPLE_RATIO_4 + * - ADC_OVERSAMPLE_RATIO_8 + * - ADC_OVERSAMPLE_RATIO_16 + * - ADC_OVERSAMPLE_RATIO_32 + * - ADC_OVERSAMPLE_RATIO_64 + * - ADC_OVERSAMPLE_RATIO_128 + * - ADC_OVERSAMPLE_RATIO_256 + * @param adc_oversample_shift: set the oversample shift. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_SHIFT_0 + * - ADC_OVERSAMPLE_SHIFT_1 + * - ADC_OVERSAMPLE_SHIFT_2 + * - ADC_OVERSAMPLE_SHIFT_3 + * - ADC_OVERSAMPLE_SHIFT_4 + * - ADC_OVERSAMPLE_SHIFT_5 + * - ADC_OVERSAMPLE_SHIFT_6 + * - ADC_OVERSAMPLE_SHIFT_7 + * - ADC_OVERSAMPLE_SHIFT_8 + * @retval none + */ +void adc_oversample_ratio_shift_set(adc_type *adc_x, adc_oversample_ratio_type adc_oversample_ratio, adc_oversample_shift_type adc_oversample_shift) +{ + adc_x->ovsp_bit.osrsel = adc_oversample_ratio; + adc_x->ovsp_bit.osssel = adc_oversample_shift; +} + +/** + * @brief enable or disable the ordinary oversampling trigger mode of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary oversampling trigger mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_oversample_trig_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.oostren = new_state; +} + +/** + * @brief set ordinary oversample restart mode of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_or_oversample_restart: ordinary oversample restart mode. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_CONTINUE + * - ADC_OVERSAMPLE_RESTART + * @retval none + */ +void adc_ordinary_oversample_restart_set(adc_type *adc_x, adc_ordinary_oversample_restart_type adc_ordinary_oversample_restart) +{ + adc_x->ovsp_bit.oosrsel = adc_ordinary_oversample_restart; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c new file mode 100644 index 0000000000..1e6c389f33 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c @@ -0,0 +1,1148 @@ +/** + ************************************************************************** + * @file at32f435_437_can.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the can firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ + +#ifdef CAN_MODULE_ENABLED + +/** @defgroup CAN_private_functions + * @{ + */ + +/** + * @brief deinitialize the can peripheral registers to their default reset values. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval none. + */ +void can_reset(can_type* can_x) +{ + if(can_x == CAN1) + { + crm_periph_reset(CRM_CAN1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_CAN1_PERIPH_RESET, FALSE); + } + else if(can_x == CAN2) + { + crm_periph_reset(CRM_CAN2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_CAN2_PERIPH_RESET, FALSE); + } +} + +/** + * @brief fill each can_baudrate_struct member with its default value. + * @param can_baudrate_struct: pointer to a can_baudrate_type structure which will be initialized. + * @retval none. + */ +void can_baudrate_default_para_init(can_baudrate_type* can_baudrate_struct) +{ + /* reset can baudrate structure parameters values */ + + /* baud rate division */ + can_baudrate_struct->baudrate_div = 1; + + /* resynchronization adjust width */ + can_baudrate_struct->rsaw_size = CAN_RSAW_2TQ; + + /* bit time segment 1 */ + can_baudrate_struct->bts1_size = CAN_BTS1_4TQ; + + /* bit time segment 2 */ + can_baudrate_struct->bts2_size = CAN_BTS2_3TQ; +} + +/** + * @brief set the baudrate of the can peripheral + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_baudrate_struct: pointer to a can_baudrate_type structure which will be set. + * @note baudrate calculate method is: + * baudrate = fpclk/(baudrate_div *(3 + bts1_size + bts2_size)) + * @retval the result of baudrate set + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_baudrate_set(can_type* can_x, can_baudrate_type* can_baudrate_struct) +{ + error_status status_index = ERROR; + uint32_t wait_ack_index = 0x00000000; + /* exit from doze mode */ + can_x->mctrl_bit.dzen = FALSE; + + /* request freeze mode */ + can_x->mctrl_bit.fzen = TRUE; + + /* wait the acknowledge */ + while((!can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledge */ + if(can_x->msts_bit.fzc) + { + can_x->btmg_bit.brdiv = can_baudrate_struct->baudrate_div - 1; + can_x->btmg_bit.rsaw = can_baudrate_struct->rsaw_size; + can_x->btmg_bit.bts1 = can_baudrate_struct->bts1_size; + can_x->btmg_bit.bts2 = can_baudrate_struct->bts2_size; + + /* request leave freeze mode */ + can_x->mctrl_bit.fzen = FALSE; + + /* wait the acknowledge */ + wait_ack_index = 0; + while((can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledged */ + if(can_x->msts_bit.fzc) + { + status_index = ERROR; + } + else + { + status_index = SUCCESS ; + } + } + else + { + status_index = ERROR; + } + + /* return the status of baudrate set */ + return status_index; +} + +/** + * @brief fill each can_init_struct member with its default value. + * @param can_base_struct: pointer to a can_base_type structure which will be initialized. + * @retval none. + */ +void can_default_para_init(can_base_type* can_base_struct) +{ + /* reset can init structure parameters values */ + + /* initialize the time triggered communication mode */ + can_base_struct->ttc_enable = FALSE; + + /* initialize the automatic exit bus-off management */ + can_base_struct->aebo_enable = FALSE; + + /* initialize the automatic exit doze mode */ + can_base_struct->aed_enable = FALSE; + + /* initialize the prohibit retransmission when sending fails */ + can_base_struct->prsf_enable = FALSE; + + /* initialize the message discarding rule select when overflow */ + can_base_struct->mdrsel_selection = CAN_DISCARDING_FIRST_RECEIVED; + + /* initialize the multiple message sending sequence rule */ + can_base_struct->mmssr_selection = CAN_SENDING_BY_ID; + + /* initialize the can_mode */ + can_base_struct->mode_selection = CAN_MODE_COMMUNICATE; +} + +/** + * @brief initialize the can peripheral according to the specified + * parameters in the can_init_struct. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_base_struct: pointer to a can_base_struct structure that contains the configuration information for the can peripheral. + * @retval the status of initialization + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_base_init(can_type* can_x, can_base_type* can_base_struct) +{ + error_status init_status_index = ERROR; + uint32_t wait_ack_index = 0x00000000; + /* exit from doze mode */ + can_x->mctrl_bit.dzen = FALSE; + + /* request freeze mode */ + can_x->mctrl_bit.fzen = TRUE; + + /* wait the acknowledge */ + while((!can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledge */ + if(can_x->msts_bit.fzc) + { + /* set the time triggered communication mode */ + can_x->mctrl_bit.ttcen = can_base_struct->ttc_enable; + + /* set the automatic exit bus-off management */ + can_x->mctrl_bit.aeboen = can_base_struct->aebo_enable; + + /* set the automatic automatic exit doze mode */ + can_x->mctrl_bit.aeden = can_base_struct->aed_enable; + + /* set the prohibit retransmission when sending fails */ + can_x->mctrl_bit.prsfen = can_base_struct->prsf_enable; + + /* set the message discarding rule select when overflow */ + can_x->mctrl_bit.mdrsel = can_base_struct->mdrsel_selection; + + /* set the multiple message sending sequence rule */ + can_x->mctrl_bit.mmssr = can_base_struct->mmssr_selection; + + /* set the test mode */ + can_x->btmg_bit.lben = can_base_struct->mode_selection & 0x01; + can_x->btmg_bit.loen = (can_base_struct->mode_selection >> 1) & 0x01; + + /* request leave freeze mode */ + can_x->mctrl_bit.fzen = FALSE; + + /* wait the acknowledge */ + wait_ack_index = 0; + while((can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledged */ + if(can_x->msts_bit.fzc) + { + init_status_index = ERROR; + } + else + { + init_status_index = SUCCESS ; + } + } + else + { + init_status_index = ERROR; + } + + /* return the status of initialization */ + return init_status_index; +} + +/** + * @brief fill each can_filter_init_struct member with its default value. + * @param can_filter_init_struct: pointer to a can_filter_init_type structure which will be initialized. + * @retval none. + */ +void can_filter_default_para_init(can_filter_init_type* can_filter_init_struct) +{ + /* reset can filter init structure parameters values */ + + /* initialize the filter activate state */ + can_filter_init_struct->filter_activate_enable = FALSE; + + /* filter mode */ + can_filter_init_struct->filter_mode = CAN_FILTER_MODE_ID_MASK; + + /* filter relation fifo select */ + can_filter_init_struct->filter_fifo = CAN_FILTER_FIFO0; + + /* filter number select */ + can_filter_init_struct->filter_number = 0; + + /* initialize the filter bit width */ + can_filter_init_struct->filter_bit = CAN_FILTER_16BIT; + + /* initialize the filters filter data bit */ + can_filter_init_struct->filter_id_high = 0; + can_filter_init_struct->filter_id_low = 0; + can_filter_init_struct->filter_mask_high = 0; + can_filter_init_struct->filter_mask_low = 0; +} + +/** + * @brief initialize the can peripheral according to the specified + * parameters in the can_filter_init_struct. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_filter_init_struct: pointer to a can_filter_init_type structure that contains the configuration information. + * @retval none. + */ +void can_filter_init(can_type* can_x, can_filter_init_type* can_filter_init_struct) +{ + uint32_t filter_number_bit_pos = 0; + filter_number_bit_pos = ((uint32_t)1) << can_filter_init_struct->filter_number; + /* set the filter turn into configuration condition */ + can_x->fctrl_bit.fcs = TRUE; + + /* filter activate disable */ + can_x->facfg &= ~(uint32_t)filter_number_bit_pos; + + /* filter bit width */ + switch(can_filter_init_struct->filter_bit) + { + case CAN_FILTER_16BIT: + can_x->fbwcfg &= ~(uint32_t)filter_number_bit_pos; + /* first 16-bit identifier and first 16-bit mask or first 16-bit identifier and second 16-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_low) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_low); + + /* second 16-bit identifier and second 16-bit mask or third 16-bit identifier and fourth 16-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_high); + + break; + case CAN_FILTER_32BIT: + can_x->fbwcfg |= filter_number_bit_pos; + /* 32-bit identifier or first 32-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_low); + + /* 32-bit mask or second 32-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_low); + + break; + default: + break; + } + + /* filter mode */ + switch(can_filter_init_struct->filter_mode) + { + case CAN_FILTER_MODE_ID_MASK: + can_x->fmcfg &= ~(uint32_t)filter_number_bit_pos; + break; + case CAN_FILTER_MODE_ID_LIST: + can_x->fmcfg |= (uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* filter relation fifo select */ + switch(can_filter_init_struct->filter_fifo) + { + case CAN_FILTER_FIFO0: + can_x->frf &= ~(uint32_t)filter_number_bit_pos; + break; + case CAN_FILTER_FIFO1: + can_x->frf |= (uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* filter activate enable */ + switch(can_filter_init_struct->filter_activate_enable) + { + case TRUE: + can_x->facfg |= (uint32_t)filter_number_bit_pos; + break; + case FALSE: + can_x->facfg &= ~(uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* set the filter turn into working condition */ + can_x->fctrl_bit.fcs = FALSE; +} + +/** + * @brief enable or disable the debug transmission prohibit of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param new_state: new state of debug transmission prohibit. + * this parameter can be: TRUE or FALSE. + * @retval none. + */ +void can_debug_transmission_prohibit(can_type* can_x, confirm_state new_state) +{ + can_x->mctrl_bit.ptd = new_state; +} + +/** + * @brief enable or disable time trigger operation communication mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param new_state : new state of time trigger operation communication mode. + * this parameter can be: TRUE or FALSE. + * @note + * note1: + * when enabled, transmit mailbox time stamp(tmts[15:0]) value is sent in the last two data bytes of + * the 8-byte message: tmts[7:0] in data byte 6 and tmts[15:8] in data byte 7 + * @note + * note2: + * tmdtbl must be programmed as 8 in order time stamp (2 bytes) to be sent over the can bus. + * @retval none + */ +void can_ttc_mode_enable(can_type* can_x, confirm_state new_state) +{ + /* config the ttc mode new_state */ + can_x->mctrl_bit.ttcen = new_state; + + /* config tmtsten bits new_state */ + can_x->tx_mailbox[0].tmc_bit.tmtsten = new_state; + can_x->tx_mailbox[1].tmc_bit.tmtsten = new_state; + can_x->tx_mailbox[2].tmc_bit.tmtsten = new_state; +} + +/** + * @brief fill the transmission message and transmit of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param tx_message_struct: pointer to a structure which contains the message to be trans. + * @retval the number of the mailbox that is used for transmission: + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * - CAN_TX_STATUS_NO_EMPTY + */ +uint8_t can_message_transmit(can_type* can_x, can_tx_message_type* tx_message_struct) +{ + uint8_t transmit_mailbox = CAN_TX_STATUS_NO_EMPTY; + + /* select one empty transmit mailbox */ + if(can_x->tsts_bit.tm0ef) + { + transmit_mailbox = CAN_TX_MAILBOX0; + } + else if(can_x->tsts_bit.tm1ef) + { + transmit_mailbox = CAN_TX_MAILBOX1; + } + else if(can_x->tsts_bit.tm2ef) + { + transmit_mailbox = CAN_TX_MAILBOX2; + } + else + { + transmit_mailbox = CAN_TX_STATUS_NO_EMPTY; + } + + if(transmit_mailbox != CAN_TX_STATUS_NO_EMPTY) + { + /* set up the id */ + can_x->tx_mailbox[transmit_mailbox].tmi &= 0x00000001; + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmidsel = tx_message_struct->id_type; + switch(tx_message_struct->id_type) + { + case CAN_ID_STANDARD: + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmsid = tx_message_struct->standard_id; + break; + case CAN_ID_EXTENDED: + can_x->tx_mailbox[transmit_mailbox].tmi |= (tx_message_struct->extended_id << 3); + break; + default: + break; + } + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmfrsel = tx_message_struct->frame_type; + /* set up the dlc */ + can_x->tx_mailbox[transmit_mailbox].tmc_bit.tmdtbl = (tx_message_struct->dlc & ((uint8_t)0x0F)); + + /* set up the data field */ + can_x->tx_mailbox[transmit_mailbox].tmdtl = (((uint32_t)tx_message_struct->data[3] << 24) | + ((uint32_t)tx_message_struct->data[2] << 16) | + ((uint32_t)tx_message_struct->data[1] << 8) | + ((uint32_t)tx_message_struct->data[0])); + can_x->tx_mailbox[transmit_mailbox].tmdth = (((uint32_t)tx_message_struct->data[7] << 24) | + ((uint32_t)tx_message_struct->data[6] << 16) | + ((uint32_t)tx_message_struct->data[5] << 8) | + ((uint32_t)tx_message_struct->data[4])); + + /* request transmission */ + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmsr = TRUE; + } + return transmit_mailbox; +} + +/** + * @brief check the transmission state of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param transmit_mailbox: the number of the mailbox that is used for transmission. + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * @retval can transmit status + * this parameter can be one of the following values: + * - CAN_TX_STATUS_SUCCESSFUL + * - CAN_TX_STATUS_FAILED + * - CAN_TX_STATUS_PENDING + */ +can_transmit_status_type can_transmit_status_get(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox) +{ + can_transmit_status_type state_index = CAN_TX_STATUS_FAILED; + switch(transmit_mailbox) + { + case CAN_TX_MAILBOX0: + if(can_x->tsts_bit.tm0tcf != RESET) + { + if(can_x->tsts_bit.tm0tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + case CAN_TX_MAILBOX1: + if(can_x->tsts_bit.tm1tcf != RESET) + { + if(can_x->tsts_bit.tm1tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + case CAN_TX_MAILBOX2: + if(can_x->tsts_bit.tm2tcf != RESET) + { + if(can_x->tsts_bit.tm2tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + default: + state_index = CAN_TX_STATUS_FAILED; + break; + } + return state_index; +} + +/** + * @brief cancel a transmit request of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param mailbox: mailbox number. + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * @retval none. + */ +void can_transmit_cancel(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox) +{ + switch (transmit_mailbox) + { + case CAN_TX_MAILBOX0: + can_x->tsts = CAN_TSTS_TM0CT_VAL; + break; + case CAN_TX_MAILBOX1: + can_x->tsts = CAN_TSTS_TM1CT_VAL; + break; + case CAN_TX_MAILBOX2: + can_x->tsts = CAN_TSTS_TM2CT_VAL; + break; + default: + break; + } +} + +/** + * @brief receive message of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: receive fifo number. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @param rx_message_struct: pointer to a structure which store the receive message. + * @retval none. + */ +void can_message_receive(can_type* can_x, can_rx_fifo_num_type fifo_number, can_rx_message_type* rx_message_struct) +{ + /* get the id type */ + rx_message_struct->id_type = (can_identifier_type)can_x->fifo_mailbox[fifo_number].rfi_bit.rfidi; + switch (rx_message_struct->id_type) + { + case CAN_ID_STANDARD: + rx_message_struct->standard_id = can_x->fifo_mailbox[fifo_number].rfi_bit.rfsid; + break; + case CAN_ID_EXTENDED: + rx_message_struct->extended_id = 0x1FFFFFFF & (can_x->fifo_mailbox[fifo_number].rfi >> 3); + break; + default: + break; + } + rx_message_struct->frame_type = (can_trans_frame_type)can_x->fifo_mailbox[fifo_number].rfi_bit.rffri; + /* get the dlc */ + rx_message_struct->dlc = can_x->fifo_mailbox[fifo_number].rfc_bit.rfdtl; + + /* get the filter match number */ + rx_message_struct->filter_index = can_x->fifo_mailbox[fifo_number].rfc_bit.rffmn; + + /* get the data field */ + rx_message_struct->data[0] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt0; + rx_message_struct->data[1] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt1; + rx_message_struct->data[2] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt2; + rx_message_struct->data[3] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt3; + rx_message_struct->data[4] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt4; + rx_message_struct->data[5] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt5; + rx_message_struct->data[6] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt6; + rx_message_struct->data[7] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt7; + + /* release the fifo */ + can_receive_fifo_release(can_x, fifo_number); +} + +/** + * @brief release the specified fifo of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: fifo to be release. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @retval none. + */ +void can_receive_fifo_release(can_type* can_x, can_rx_fifo_num_type fifo_number) +{ + switch (fifo_number) + { + case CAN_RX_FIFO0: + can_x->rf0 = CAN_RF0_RF0R_VAL; + break; + case CAN_RX_FIFO1: + can_x->rf1 = CAN_RF1_RF1R_VAL; + break; + default: + break; + } +} + +/** + * @brief return the number of pending messages of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: receive fifo number. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @retval the number of message pending in the receive fifo. + */ +uint8_t can_receive_message_pending_get(can_type* can_x, can_rx_fifo_num_type fifo_number) +{ + uint8_t message_pending = 0; + switch (fifo_number) + { + case CAN_RX_FIFO0: + message_pending = can_x->rf0_bit.rf0mn; + break; + case CAN_RX_FIFO1: + message_pending = can_x->rf1_bit.rf1mn; + break; + default: + break; + } + return message_pending; +} + +/** + * @brief set the operation mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_operating_mode: can operating mode. + * this parameter can be one of the following values: + * - CAN_OPERATINGMODE_FREEZE + * - CAN_OPERATINGMODE_DOZE + * - CAN_OPERATINGMODE_COMMUNICATE + * @retval status of operation mode set + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_operating_mode_set(can_type* can_x, can_operating_mode_type can_operating_mode) +{ + error_status status = ERROR; + uint32_t time_out_index = FZC_TIMEOUT; + + if (can_operating_mode == CAN_OPERATINGMODE_FREEZE) + { + /* request enter freeze mode */ + can_x->mctrl_bit.dzen = FALSE; + can_x->mctrl_bit.fzen = TRUE; + + while(((can_x->msts_bit.dzc) || (!can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((can_x->msts_bit.dzc) || (!can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else if(can_operating_mode == CAN_OPERATINGMODE_DOZE) + { + /* request enter doze mode */ + can_x->mctrl_bit.dzen = TRUE; + can_x->mctrl_bit.fzen = FALSE; + + while(((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else if(can_operating_mode == CAN_OPERATINGMODE_COMMUNICATE) + { + /* request enter normal mode */ + can_x->mctrl_bit.dzen = FALSE; + can_x->mctrl_bit.fzen = FALSE; + + while(((can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = ERROR; + } + return status; +} + +/** + * @brief enter the low power mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval status of doze mode enter, the returned value can be: + * - CAN_ENTER_DOZE_SUCCESSFUL + * - CAN_ENTER_DOZE_FAILED + */ +can_enter_doze_status_type can_doze_mode_enter(can_type* can_x) +{ + can_enter_doze_status_type status = CAN_ENTER_DOZE_FAILED; + uint32_t time_out_index = FZC_TIMEOUT; + can_x->mctrl_bit.fzen = FALSE; + can_x->mctrl_bit.dzen = TRUE; + while(((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = CAN_ENTER_DOZE_FAILED; + } + else + { + status = CAN_ENTER_DOZE_SUCCESSFUL; + } + return status; +} + +/** + * @brief exit the doze mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval status of doze mode enter, the returned value can be: + * - CAN_QUIT_DOZE_SUCCESSFUL + * - CAN_QUIT_DOZE_FAILED + */ +can_quit_doze_status_type can_doze_mode_exit(can_type* can_x) +{ + can_quit_doze_status_type status = CAN_QUIT_DOZE_FAILED; + uint32_t time_out_index = DZC_TIMEOUT; + can_x->mctrl_bit.dzen = FALSE; + while((can_x->msts_bit.dzc) && (time_out_index != 0)) + { + time_out_index--; + } + if(!can_x->msts_bit.dzc) + { + status = CAN_QUIT_DOZE_SUCCESSFUL; + } + return status; +} + +/** + * @brief return the error type record (etr) of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of the error code + * the return can be one of the follow values: + * - CAN_ERRORRECORD_NOERR + * - CAN_ERRORRECORD_STUFFERR, + * - CAN_ERRORRECORD_FORMERR, + * - CAN_ERRORRECORD_ACKERR, + * - CAN_ERRORRECORD_BITRECESSIVEERR, + * - CAN_ERRORRECORD_BITDOMINANTERR, + * - CAN_ERRORRECORD_CRCERR, + * - CAN_ERRORRECORD_SOFTWARESETERR + */ +can_error_record_type can_error_type_record_get(can_type* can_x) +{ + can_error_record_type error_code = CAN_ERRORRECORD_NOERR; + + error_code = (can_error_record_type)can_x->ests_bit.etr; + return error_code; +} + +/** + * @brief return the receive error counter (rec) of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of receive error counter. + */ +uint8_t can_receive_error_counter_get(can_type* can_x) +{ + uint8_t counter = 0; + counter = can_x->ests_bit.rec; + return counter; +} + +/** + * @brief return the transmit error counter of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of transmit error counter. + */ +uint8_t can_transmit_error_counter_get(can_type* can_x) +{ + uint8_t counter = 0; + counter = can_x->ests_bit.tec; + return counter; +} + +/** + * @brief enable or disable the interrupt of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_int: specifies the can interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - CAN_TCIEN_INT + * - CAN_RF0MIEN_INT + * - CAN_RF0FIEN_INT + * - CAN_RF0OIEN_INT + * - CAN_RF1MIEN_INT + * - CAN_RF1FIEN_INT + * - CAN_RF1OIEN_INT + * - CAN_EAIEN_INT + * - CAN_EPIEN_INT + * - CAN_BOIEN_INT + * - CAN_ETRIEN_INT + * - CAN_EOIEN_INT + * - CAN_QDZIEN_INT + * - CAN_EDZIEN_INT + * @param new_state: new state of the can interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none. + */ +void can_interrupt_enable(can_type* can_x, uint32_t can_int, confirm_state new_state) +{ + if (new_state != FALSE) + { + can_x->inten |= can_int; + } + else + { + can_x->inten &= ~can_int; + } +} + +/** + * @brief get flag of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_flag: select the flag. + * this parameter can be one of the following flags: + * - CAN_EAF_FLAG + * - CAN_EPF_FLAG + * - CAN_BOF_FLAG + * - CAN_ETR_FLAG + * - CAN_EOIF_FLAG + * - CAN_TM0TCF_FLAG + * - CAN_TM1TCF_FLAG + * - CAN_TM2TCF_FLAG + * - CAN_RF0MN_FLAG + * - CAN_RF0FF_FLAG + * - CAN_RF0OF_FLAG + * - CAN_RF1MN_FLAG + * - CAN_RF1FF_FLAG + * - CAN_RF1OF_FLAG + * - CAN_QDZIF_FLAG + * - CAN_EDZC_FLAG + * - CAN_TMEF_FLAG + * note:the state of CAN_EDZC_FLAG need to check dzc and edzif bit + * note:the state of CAN_TMEF_FLAG need to check rqc0,rqc1 and rqc2 bit + * @retval status of can_flag, the returned value can be:SET or RESET. + */ +flag_status can_flag_get(can_type* can_x, uint32_t can_flag) +{ + flag_status bit_status = RESET; + switch(can_flag) + { + case CAN_EAF_FLAG: + bit_status = (flag_status)can_x->ests_bit.eaf; + break; + case CAN_EPF_FLAG: + bit_status = (flag_status)can_x->ests_bit.epf; + break; + case CAN_BOF_FLAG: + bit_status = (flag_status)can_x->ests_bit.bof; + break; + case CAN_ETR_FLAG: + if(can_x->ests_bit.etr != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_EOIF_FLAG: + bit_status = (flag_status)can_x->msts_bit.eoif; + break; + case CAN_TM0TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm0tcf; + break; + case CAN_TM1TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm1tcf; + break; + case CAN_TM2TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm2tcf; + break; + case CAN_RF0MN_FLAG: + if(can_x->rf0_bit.rf0mn != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_RF0FF_FLAG: + bit_status = (flag_status)can_x->rf0_bit.rf0ff; + break; + case CAN_RF0OF_FLAG: + bit_status = (flag_status)can_x->rf0_bit.rf0of; + break; + case CAN_RF1MN_FLAG: + if(can_x->rf1_bit.rf1mn != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_RF1FF_FLAG: + bit_status = (flag_status)can_x->rf1_bit.rf1ff; + break; + case CAN_RF1OF_FLAG: + bit_status = (flag_status)can_x->rf1_bit.rf1of; + break; + case CAN_QDZIF_FLAG: + bit_status = (flag_status)can_x->msts_bit.qdzif; + break; + case CAN_EDZC_FLAG: + if((can_x->msts_bit.dzc != RESET) ||(can_x->msts_bit.edzif != RESET)) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_TMEF_FLAG: + if((can_x->tsts_bit.tm0ef != RESET) || (can_x->tsts_bit.tm1ef != RESET) || (can_x->tsts_bit.tm2ef != RESET)) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + default: + bit_status = RESET; + break; + } + return bit_status; +} + +/** + * @brief clear flag of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_flag: select the flag. + * this parameter can be one of the following flags: + * - CAN_EAF_FLAG + * - CAN_EPF_FLAG + * - CAN_BOF_FLAG + * - CAN_ETR_FLAG + * - CAN_EOIF_FLAG + * - CAN_TM0TCF_FLAG + * - CAN_TM1TCF_FLAG + * - CAN_TM2TCF_FLAG + * - CAN_RF0FF_FLAG + * - CAN_RF0OF_FLAG + * - CAN_RF1FF_FLAG + * - CAN_RF1OF_FLAG + * - CAN_QDZIF_FLAG + * - CAN_EDZC_FLAG + * - CAN_TMEF_FLAG + * note:CAN_RF0MN_FLAG and CAN_RF1MN_FLAG can not clear by this function + * @retval none. + */ +void can_flag_clear(can_type* can_x, uint32_t can_flag) +{ + switch(can_flag) + { + case CAN_EAF_FLAG: + case CAN_EPF_FLAG: + case CAN_BOF_FLAG: + case CAN_EOIF_FLAG: + can_x->msts = CAN_MSTS_EOIF_VAL; + break; + case CAN_ETR_FLAG: + can_x->msts = CAN_MSTS_EOIF_VAL; + can_x->ests = 0; + break; + case CAN_TM0TCF_FLAG: + can_x->tsts = CAN_TSTS_TM0TCF_VAL; + break; + case CAN_TM1TCF_FLAG: + can_x->tsts = CAN_TSTS_TM1TCF_VAL; + break; + case CAN_TM2TCF_FLAG: + can_x->tsts = CAN_TSTS_TM2TCF_VAL; + break; + case CAN_RF0FF_FLAG: + can_x->rf0 = CAN_RF0_RF0FF_VAL; + break; + case CAN_RF0OF_FLAG: + can_x->rf0 = CAN_RF0_RF0OF_VAL; + break; + case CAN_RF1FF_FLAG: + can_x->rf1 = CAN_RF1_RF1FF_VAL; + break; + case CAN_RF1OF_FLAG: + can_x->rf1 = CAN_RF1_RF1OF_VAL; + break; + case CAN_QDZIF_FLAG: + can_x->msts = CAN_MSTS_QDZIF_VAL; + break; + case CAN_EDZC_FLAG: + can_x->msts = CAN_MSTS_EDZIF_VAL; + break; + case CAN_TMEF_FLAG: + can_x->tsts = CAN_TSTS_TM0TCF_VAL | CAN_TSTS_TM1TCF_VAL | CAN_TSTS_TM2TCF_VAL; + break; + default: + break; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c new file mode 100644 index 0000000000..326ed49ebe --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c @@ -0,0 +1,164 @@ +/** + ************************************************************************** + * @file at32f435_437_crc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the crc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +#ifdef CRC_MODULE_ENABLED + +/** @defgroup CRC_private_functions + * @{ + */ + +/** + * @brief reset the crc data register. + * @param none + * @retval none + */ +void crc_data_reset(void) +{ + /* reset crc generator */ + CRC->ctrl_bit.rst = 0x1; +} + +/** + * @brief compute the 32-bit crc of a given data word(32-bit). + * @param data: data word(32-bit) to compute its crc + * @retval 32-bit crc + */ +uint32_t crc_one_word_calculate(uint32_t data) +{ + CRC->dt = data; + return (CRC->dt); +} + +/** + * @brief compute the 32-bit crc of a given buffer of data word(32-bit). + * @param pbuffer: pointer to the buffer containing the data to be computed + * @param length: length of the buffer to be computed + * @retval 32-bit crc + */ +uint32_t crc_block_calculate(uint32_t *pbuffer, uint32_t length) +{ + uint32_t index = 0; + + for(index = 0; index < length; index++) + { + CRC->dt = pbuffer[index]; + } + + return (CRC->dt); +} + +/** + * @brief return the current crc value. + * @param none + * @retval 32-bit crc + */ +uint32_t crc_data_get(void) +{ + return (CRC->dt); +} + +/** + * @brief store a 8-bit data in the common data register. + * @param cdt_value: 8-bit value to be stored in the common data register + * @retval none + */ +void crc_common_data_set(uint8_t cdt_value) +{ + CRC->cdt_bit.cdt = cdt_value; +} + +/** + * @brief return the 8-bit data stored in the common data register + * @param none + * @retval 8-bit value of the common data register + */ +uint8_t crc_common_data_get(void) +{ + return (CRC->cdt_bit.cdt); +} + +/** + * @brief set the 32-bit initial data of crc + * @param value: initial data + * @retval none + */ +void crc_init_data_set(uint32_t value) +{ + CRC->idt = value; +} + +/** + * @brief control the reversal of the bit order in the input data + * @param value + * this parameter can be one of the following values: + * - CRC_REVERSE_INPUT_NO_AFFECTE + * - CRC_REVERSE_INPUT_BY_BYTE + * - CRC_REVERSE_INPUT_BY_HALFWORD + * - CRC_REVERSE_INPUT_BY_WORD + * @retval none. + */ +void crc_reverse_input_data_set(crc_reverse_input_type value) +{ + CRC->ctrl_bit.revid = value; +} + +/** + * @brief control the reversal of the bit order in the output data + * @param value + * this parameter can be one of the following values: + * - CRC_REVERSE_OUTPUT_NO_AFFECTE + * - CRC_REVERSE_OUTPUT_DATA + * @retval none. + */ +void crc_reverse_output_data_set(crc_reverse_output_type value) +{ + CRC->ctrl_bit.revod = value; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c new file mode 100644 index 0000000000..c8523ba41e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c @@ -0,0 +1,986 @@ +/** + ************************************************************************** + * @file at32f435_437_crm.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the crm firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CRM + * @brief CRM driver modules + * @{ + */ + +#ifdef CRM_MODULE_ENABLED + +/** @defgroup CRM_private_functions + * @{ + */ + +/** + * @brief reset the crm register + * @param none + * @retval none + */ +void crm_reset(void) +{ + /* reset the crm clock configuration to the default reset state(for debug purpose) */ + /* set hicken bit */ + CRM->ctrl_bit.hicken = TRUE; + + /* wait hick stable */ + while(CRM->ctrl_bit.hickstbl != SET); + + /* hick used as system clock */ + CRM->cfg_bit.sclksel = CRM_SCLK_HICK; + + /* wait sclk switch status */ + while(CRM->cfg_bit.sclksts != CRM_SCLK_HICK); + + /* reset hexten, hextbyps, cfden and pllen bits */ + CRM->ctrl &= ~(0x010D0000U); + + /* reset cfg register, include sclk switch, ahbdiv, apb1div, apb2div, adcdiv, clkout bits */ + CRM->cfg = 0; + + /* reset pllms pllns pllfr pllrcs bits */ + CRM->pllcfg = 0x00033002U; + + /* reset clkout[3], usbbufs, hickdiv, clkoutdiv */ + CRM->misc1 = 0; + + /* disable all interrupts enable and clear pending bits */ + CRM->clkint = 0x009F0000U; +} + +/** + * @brief enable or disable crm low speed external crystal bypass + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_lext_bypass(confirm_state new_state) +{ + CRM->bpdc_bit.lextbyps = new_state; +} + +/** + * @brief enable or disable crm high speed external crystal bypass + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_hext_bypass(confirm_state new_state) +{ + CRM->ctrl_bit.hextbyps = new_state; +} + +/** + * @brief get crm flag status + * @param flag + * this parameter can be one of the following values: + * - CRM_HICK_STABLE_FLAG + * - CRM_HEXT_STABLE_FLAG + * - CRM_PLL_STABLE_FLAG + * - CRM_LEXT_STABLE_FLAG + * - CRM_LICK_STABLE_FLAG + * - CRM_PIN_RESET_FLAG + * - CRM_POR_RESET_FLAG + * - CRM_SW_RESET_FLAG + * - CRM_WDT_RESET_FLAG + * - CRM_WWDT_RESET_FLAG + * - CRM_LOWPOWER_RESET_FLAG + * interrupt flag: + * - CRM_LICK_READY_INT_FLAG + * - CRM_LEXT_READY_INT_FLAG + * - CRM_HICK_READY_INT_FLAG + * - CRM_HEXT_READY_INT_FLAG + * - CRM_PLL_READY_INT_FLAG + * - CRM_CLOCK_FAILURE_INT_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status crm_flag_get(uint32_t flag) +{ + flag_status status = RESET; + if((CRM_REG(flag) & CRM_REG_BIT(flag)) != CRM_REG_BIT(flag)) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief wait for hext stable + * @param none + * @retval error_status (ERROR or SUCCESS) + */ +error_status crm_hext_stable_wait(void) +{ + uint32_t stable_cnt = 0; + error_status status = ERROR; + + while((crm_flag_get(CRM_HEXT_STABLE_FLAG) != SET) && (stable_cnt < HEXT_STARTUP_TIMEOUT)) + { + stable_cnt ++; + } + + if(crm_flag_get(CRM_HEXT_STABLE_FLAG) != SET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + + return status; +} + +/** + * @brief set the hick trimming value + * @param trim_value (0x00~0x3F) + * @retval none + */ +void crm_hick_clock_trimming_set(uint8_t trim_value) +{ + CRM->ctrl_bit.hicktrim = trim_value; +} + +/** + * @brief set the crm calibration value + * @param cali_value (0x00~0xFF) + * @retval none + */ +void crm_hick_clock_calibration_set(uint8_t cali_value) +{ + /* enable write hick calibration */ + CRM->misc1_bit.hickcal_key = 0x5A; + + /* write hick calibration value */ + CRM->ctrl_bit.hickcal = cali_value; + + /* disable write hick calibration */ + CRM->misc1_bit.hickcal_key = 0x0; +} + +/** + * @brief enable or disable the peripheral clock + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_CLOCK - CRM_GPIOB_PERIPH_CLOCK - CRM_GPIOC_PERIPH_CLOCK - CRM_GPIOD_PERIPH_CLOCK + * - CRM_GPIOE_PERIPH_CLOCK - CRM_GPIOF_PERIPH_CLOCK - CRM_GPIOG_PERIPH_CLOCK - CRM_GPIOH_PERIPH_CLOCK + * - CRM_CRC_PERIPH_CLOCK - CRM_EDMA_PERIPH_CLOCK - CRM_DMA1_PERIPH_CLOCK - CRM_DMA2_PERIPH_CLOCK + * - CRM_EMAC_PERIPH_CLOCK - CRM_EMACTX_PERIPH_CLOCK - CRM_EMACRX_PERIPH_CLOCK - CRM_EMACPTP_PERIPH_CLOCK + * - CRM_OTGFS2_PERIPH_CLOCK - CRM_DVP_PERIPH_CLOCK - CRM_OTGFS1_PERIPH_CLOCK - CRM_SDIO1_PERIPH_CLOCK + * - CRM_XMC_PERIPH_CLOCK - CRM_QSPI1_PERIPH_CLOCK - CRM_QSPI2_PERIPH_CLOCK - CRM_SDIO2_PERIPH_CLOCK + * - CRM_TMR2_PERIPH_CLOCK - CRM_TMR3_PERIPH_CLOCK - CRM_TMR4_PERIPH_CLOCK - CRM_TMR5_PERIPH_CLOCK + * - CRM_TMR6_PERIPH_CLOCK - CRM_TMR7_PERIPH_CLOCK - CRM_TMR12_PERIPH_CLOCK - CRM_TMR13_PERIPH_CLOCK + * - CRM_TMR14_PERIPH_CLOCK - CRM_WWDT_PERIPH_CLOCK - CRM_SPI2_PERIPH_CLOCK - CRM_SPI3_PERIPH_CLOCK + * - CRM_USART2_PERIPH_CLOCK - CRM_USART3_PERIPH_CLOCK - CRM_UART4_PERIPH_CLOCK - CRM_UART5_PERIPH_CLOCK + * - CRM_I2C1_PERIPH_CLOCK - CRM_I2C2_PERIPH_CLOCK - CRM_I2C3_PERIPH_CLOCK - CRM_CAN1_PERIPH_CLOCK + * - CRM_CAN2_PERIPH_CLOCK - CRM_PWC_PERIPH_CLOCK - CRM_DAC_PERIPH_CLOCK - CRM_UART7_PERIPH_CLOCK + * - CRM_UART8_PERIPH_CLOCK - CRM_TMR1_PERIPH_CLOCK - CRM_TMR8_PERIPH_CLOCK - CRM_USART1_PERIPH_CLOCK + * - CRM_USART6_PERIPH_CLOCK - CRM_ADC1_PERIPH_CLOCK - CRM_ADC2_PERIPH_CLOCK - CRM_ADC3_PERIPH_CLOCK + * - CRM_SPI1_PERIPH_CLOCK - CRM_SPI4_PERIPH_CLOCK - CRM_SCFG_PERIPH_CLOCK - CRM_TMR9_PERIPH_CLOCK + * - CRM_TMR10_PERIPH_CLOCK - CRM_TMR11_PERIPH_CLOCK - CRM_TMR20_PERIPH_CLOCK - CRM_ACC_PERIPH_CLOCK + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_clock_enable(crm_periph_clock_type value, confirm_state new_state) +{ + /* enable periph clock */ + if(TRUE == new_state) + { + CRM_REG(value) |= CRM_REG_BIT(value); + } + /* disable periph clock */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the peripheral reset + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_RESET - CRM_GPIOB_PERIPH_RESET - CRM_GPIOC_PERIPH_RESET - CRM_GPIOD_PERIPH_RESET + * - CRM_GPIOE_PERIPH_RESET - CRM_GPIOF_PERIPH_RESET - CRM_GPIOG_PERIPH_RESET - CRM_GPIOH_PERIPH_RESET + * - CRM_CRC_PERIPH_RESET - CRM_EDMA_PERIPH_RESET - CRM_DMA1_PERIPH_RESET - CRM_DMA2_PERIPH_RESET + * - CRM_EMAC_PERIPH_RESET - CRM_OTGFS2_PERIPH_RESET - CRM_DVP_PERIPH_RESET - CRM_OTGFS1_PERIPH_RESET + * - CRM_SDIO1_PERIPH_RESET - CRM_XMC_PERIPH_RESET - CRM_QSPI1_PERIPH_RESET - CRM_QSPI2_PERIPH_RESET + * - CRM_SDIO2_PERIPH_RESET - CRM_TMR2_PERIPH_RESET - CRM_TMR3_PERIPH_RESET - CRM_TMR4_PERIPH_RESET + * - CRM_TMR5_PERIPH_RESET - CRM_TMR6_PERIPH_RESET - CRM_TMR7_PERIPH_RESET - CRM_TMR12_PERIPH_RESET + * - CRM_TMR13_PERIPH_RESET - CRM_TMR14_PERIPH_RESET - CRM_WWDT_PERIPH_RESET - CRM_SPI2_PERIPH_RESET + * - CRM_SPI3_PERIPH_RESET - CRM_USART2_PERIPH_RESET - CRM_USART3_PERIPH_RESET - CRM_UART4_PERIPH_RESET + * - CRM_UART5_PERIPH_RESET - CRM_I2C1_PERIPH_RESET - CRM_I2C2_PERIPH_RESET - CRM_I2C3_PERIPH_RESET + * - CRM_CAN1_PERIPH_RESET - CRM_CAN2_PERIPH_RESET - CRM_PWC_PERIPH_RESET - CRM_DAC_PERIPH_RESET + * - CRM_UART7_PERIPH_RESET - CRM_UART8_PERIPH_RESET - CRM_TMR1_PERIPH_RESET - CRM_TMR8_PERIPH_RESET + * - CRM_USART1_PERIPH_RESET - CRM_USART6_PERIPH_RESET - CRM_ADC_PERIPH_RESET - CRM_SPI1_PERIPH_RESET + * - CRM_SPI4_PERIPH_RESET - CRM_SCFG_PERIPH_RESET - CRM_TMR9_PERIPH_RESET - CRM_TMR10_PERIPH_RESET + * - CRM_TMR11_PERIPH_RESET - CRM_TMR20_PERIPH_RESET - CRM_ACC_PERIPH_RESET + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_reset(crm_periph_reset_type value, confirm_state new_state) +{ + /* enable periph reset */ + if(new_state == TRUE) + { + CRM_REG(value) |= (CRM_REG_BIT(value)); + } + /* disable periph reset */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the peripheral clock in lowpower mode + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_LOWPOWER - CRM_GPIOB_PERIPH_LOWPOWER - CRM_GPIOC_PERIPH_LOWPOWER - CRM_GPIOD_PERIPH_LOWPOWER + * - CRM_GPIOE_PERIPH_LOWPOWER - CRM_GPIOF_PERIPH_LOWPOWER - CRM_GPIOG_PERIPH_LOWPOWER - CRM_GPIOH_PERIPH_LOWPOWER + * - CRM_CRC_PERIPH_LOWPOWER - CRM_EDMA_PERIPH_LOWPOWER - CRM_DMA1_PERIPH_LOWPOWER - CRM_DMA2_PERIPH_LOWPOWER + * - CRM_EMAC_PERIPH_LOWPOWER - CRM_EMACTX_PERIPH_LOWPOWER - CRM_EMACRX_PERIPH_LOWPOWER - CRM_EMACPTP_PERIPH_LOWPOWER + * - CRM_OTGFS2_PERIPH_LOWPOWER - CRM_DVP_PERIPH_LOWPOWER - CRM_OTGFS1_PERIPH_LOWPOWER - CRM_SDIO1_PERIPH_LOWPOWER + * - CRM_XMC_PERIPH_LOWPOWER - CRM_QSPI1_PERIPH_LOWPOWER - CRM_QSPI2_PERIPH_LOWPOWER - CRM_SDIO2_PERIPH_LOWPOWER + * - CRM_TMR2_PERIPH_LOWPOWER - CRM_TMR3_PERIPH_LOWPOWER - CRM_TMR4_PERIPH_LOWPOWER - CRM_TMR5_PERIPH_LOWPOWER + * - CRM_TMR6_PERIPH_LOWPOWER - CRM_TMR7_PERIPH_LOWPOWER - CRM_TMR12_PERIPH_LOWPOWER - CRM_TMR13_PERIPH_LOWPOWER + * - CRM_TMR14_PERIPH_LOWPOWER - CRM_WWDT_PERIPH_LOWPOWER - CRM_SPI2_PERIPH_LOWPOWER - CRM_SPI3_PERIPH_LOWPOWER + * - CRM_USART2_PERIPH_LOWPOWER - CRM_USART3_PERIPH_LOWPOWER - CRM_UART4_PERIPH_LOWPOWER - CRM_UART5_PERIPH_LOWPOWER + * - CRM_I2C1_PERIPH_LOWPOWER - CRM_I2C2_PERIPH_LOWPOWER - CRM_I2C3_PERIPH_LOWPOWER - CRM_CAN1_PERIPH_LOWPOWER + * - CRM_CAN2_PERIPH_LOWPOWER - CRM_PWC_PERIPH_LOWPOWER - CRM_DAC_PERIPH_LOWPOWER - CRM_UART7_PERIPH_LOWPOWER + * - CRM_UART8_PERIPH_LOWPOWER - CRM_TMR1_PERIPH_LOWPOWER - CRM_TMR8_PERIPH_LOWPOWER - CRM_USART1_PERIPH_LOWPOWER + * - CRM_USART6_PERIPH_LOWPOWER - CRM_ADC1_PERIPH_LOWPOWER - CRM_ADC2_PERIPH_LOWPOWER - CRM_ADC3_PERIPH_LOWPOWER + * - CRM_SPI1_PERIPH_LOWPOWER - CRM_SPI4_PERIPH_LOWPOWER - CRM_SCFG_PERIPH_LOWPOWER - CRM_TMR9_PERIPH_LOWPOWER + * - CRM_TMR10_PERIPH_LOWPOWER - CRM_TMR11_PERIPH_LOWPOWER - CRM_TMR20_PERIPH_LOWPOWER - CRM_ACC_PERIPH_LOWPOWER + * - CRM_FLASH_PERIPH_LOWPOWER - CRM_SRAM1_PERIPH_LOWPOWER - CRM_SRAM2_PERIPH_LOWPOWER + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_lowpower_mode_enable(crm_periph_clock_lowpower_type value, confirm_state new_state) +{ + /* enable periph clock in lowpower mode */ + if(new_state == TRUE) + { + CRM_REG(value) |= (CRM_REG_BIT(value)); + } + /* disable periph clock in lowpower mode */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the crm clock source + * @param source + * this parameter can be one of the following values: + * - CRM_CLOCK_SOURCE_HICK + * - CRM_CLOCK_SOURCE_HEXT + * - CRM_CLOCK_SOURCE_PLL + * - CRM_CLOCK_SOURCE_LEXT + * - CRM_CLOCK_SOURCE_LICK + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clock_source_enable(crm_clock_source_type source, confirm_state new_state) +{ + switch(source) + { + case CRM_CLOCK_SOURCE_HICK: + CRM->ctrl_bit.hicken = new_state; + break; + case CRM_CLOCK_SOURCE_HEXT: + CRM->ctrl_bit.hexten = new_state; + break; + case CRM_CLOCK_SOURCE_PLL: + CRM->ctrl_bit.pllen = new_state; + break; + case CRM_CLOCK_SOURCE_LEXT: + CRM->bpdc_bit.lexten = new_state; + break; + case CRM_CLOCK_SOURCE_LICK: + CRM->ctrlsts_bit.licken = new_state; + break; + default: break; + } +} + +/** + * @brief clear the crm reset flags + * @param flag + * this parameter can be one of the following values: + * reset flag: + * - CRM_PIN_RESET_FLAG + * - CRM_POR_RESET_FLAG + * - CRM_SW_RESET_FLAG + * - CRM_WDT_RESET_FLAG + * - CRM_WWDT_RESET_FLAG + * - CRM_LOWPOWER_RESET_FLAG + * - CRM_ALL_RESET_FLAG + * interrupt flag: + * - CRM_LICK_READY_INT_FLAG + * - CRM_LEXT_READY_INT_FLAG + * - CRM_HICK_READY_INT_FLAG + * - CRM_HEXT_READY_INT_FLAG + * - CRM_PLL_READY_INT_FLAG + * - CRM_CLOCK_FAILURE_INT_FLAG + * @retval none + */ +void crm_flag_clear(uint32_t flag) +{ + switch(flag) + { + case CRM_NRST_RESET_FLAG: + case CRM_POR_RESET_FLAG: + case CRM_SW_RESET_FLAG: + case CRM_WDT_RESET_FLAG: + case CRM_WWDT_RESET_FLAG: + case CRM_LOWPOWER_RESET_FLAG: + case CRM_ALL_RESET_FLAG: + CRM->ctrlsts_bit.rstfc = TRUE; + while(CRM->ctrlsts_bit.rstfc == TRUE); + break; + case CRM_LICK_READY_INT_FLAG: + CRM->clkint_bit.lickstblfc = TRUE; + break; + case CRM_LEXT_READY_INT_FLAG: + CRM->clkint_bit.lextstblfc = TRUE; + break; + case CRM_HICK_READY_INT_FLAG: + CRM->clkint_bit.hickstblfc = TRUE; + break; + case CRM_HEXT_READY_INT_FLAG: + CRM->clkint_bit.hextstblfc = TRUE; + break; + case CRM_PLL_READY_INT_FLAG: + CRM->clkint_bit.pllstblfc = TRUE; + break; + case CRM_CLOCK_FAILURE_INT_FLAG: + CRM->clkint_bit.cfdfc = TRUE; + break; + default: + break; + } +} + +/** + * @brief select ertc clock + * @param value + * this parameter can be one of the following values: + * - CRM_ERTC_CLOCK_NOCLK + * - CRM_ERTC_CLOCK_LEXT + * - CRM_ERTC_CLOCK_LICK + * - CRM_ERTC_CLOCK_HEXT_DIV_2 + * - CRM_ERTC_CLOCK_HEXT_DIV_3 + * - CRM_ERTC_CLOCK_HEXT_DIV_4 + * - CRM_ERTC_CLOCK_HEXT_DIV_5 + * - CRM_ERTC_CLOCK_HEXT_DIV_6 + * - CRM_ERTC_CLOCK_HEXT_DIV_7 + * - CRM_ERTC_CLOCK_HEXT_DIV_8 + * - CRM_ERTC_CLOCK_HEXT_DIV_9 + * - CRM_ERTC_CLOCK_HEXT_DIV_10 + * - CRM_ERTC_CLOCK_HEXT_DIV_11 + * - CRM_ERTC_CLOCK_HEXT_DIV_12 + * - CRM_ERTC_CLOCK_HEXT_DIV_13 + * - CRM_ERTC_CLOCK_HEXT_DIV_14 + * - CRM_ERTC_CLOCK_HEXT_DIV_15 + * - CRM_ERTC_CLOCK_HEXT_DIV_16 + * - CRM_ERTC_CLOCK_HEXT_DIV_17 + * - CRM_ERTC_CLOCK_HEXT_DIV_18 + * - CRM_ERTC_CLOCK_HEXT_DIV_19 + * - CRM_ERTC_CLOCK_HEXT_DIV_20 + * - CRM_ERTC_CLOCK_HEXT_DIV_21 + * - CRM_ERTC_CLOCK_HEXT_DIV_22 + * - CRM_ERTC_CLOCK_HEXT_DIV_23 + * - CRM_ERTC_CLOCK_HEXT_DIV_24 + * - CRM_ERTC_CLOCK_HEXT_DIV_25 + * - CRM_ERTC_CLOCK_HEXT_DIV_26 + * - CRM_ERTC_CLOCK_HEXT_DIV_27 + * - CRM_ERTC_CLOCK_HEXT_DIV_28 + * - CRM_ERTC_CLOCK_HEXT_DIV_29 + * - CRM_ERTC_CLOCK_HEXT_DIV_30 + * - CRM_ERTC_CLOCK_HEXT_DIV_31 + * @retval none + */ +void crm_ertc_clock_select(crm_ertc_clock_type value) +{ + CRM->cfg_bit.ertcdiv = ((value & 0x1F0) >> 4); + CRM->bpdc_bit.ertcsel = (value & 0xF); +} + +/** + * @brief enable or disable ertc + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_ertc_clock_enable(confirm_state new_state) +{ + CRM->bpdc_bit.ertcen = new_state; +} + +/** + * @brief set crm ahb division + * @param value + * this parameter can be one of the following values: + * - CRM_AHB_DIV_1 + * - CRM_AHB_DIV_2 + * - CRM_AHB_DIV_4 + * - CRM_AHB_DIV_8 + * - CRM_AHB_DIV_16 + * - CRM_AHB_DIV_64 + * - CRM_AHB_DIV_128 + * - CRM_AHB_DIV_256 + * - CRM_AHB_DIV_512 + * @retval none + */ +void crm_ahb_div_set(crm_ahb_div_type value) +{ + CRM->cfg_bit.ahbdiv = value; +} + +/** + * @brief set crm apb1 division + * @param value + * this parameter can be one of the following values: + * - CRM_APB1_DIV_1 + * - CRM_APB1_DIV_2 + * - CRM_APB1_DIV_4 + * - CRM_APB1_DIV_8 + * - CRM_APB1_DIV_16 + * @retval none + */ +void crm_apb1_div_set(crm_apb1_div_type value) +{ + CRM->cfg_bit.apb1div = value; +} + +/** + * @brief set crm apb2 division + * @param value + * this parameter can be one of the following values: + * - CRM_APB2_DIV_1 + * - CRM_APB2_DIV_2 + * - CRM_APB2_DIV_4 + * - CRM_APB2_DIV_8 + * - CRM_APB2_DIV_16 + * @retval none + */ +void crm_apb2_div_set(crm_apb2_div_type value) +{ + CRM->cfg_bit.apb2div = value; +} + +/** + * @brief set usb division + * @param value + * this parameter can be one of the following values: + * - CRM_USB_DIV_1_5 + * - CRM_USB_DIV_1 + * - CRM_USB_DIV_2_5 + * - CRM_USB_DIV_2 + * - CRM_USB_DIV_3_5 + * - CRM_USB_DIV_3 + * - CRM_USB_DIV_4_5 + * - CRM_USB_DIV_4 + * - CRM_USB_DIV_5_5 + * - CRM_USB_DIV_5 + * - CRM_USB_DIV_6_5 + * - CRM_USB_DIV_6 + * - CRM_USB_DIV_7 + * @retval none + */ +void crm_usb_clock_div_set(crm_usb_div_type value) +{ + CRM->misc2_bit.usbdiv = value; +} + +/** + * @brief enable or disable clock failure detection + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clock_failure_detection_enable(confirm_state new_state) +{ + CRM->ctrl_bit.cfden = new_state; +} + +/** + * @brief battery powered domain software reset + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_battery_powered_domain_reset(confirm_state new_state) +{ + CRM->bpdc_bit.bpdrst = new_state; +} + +/** + * @brief auto step clock switch enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_auto_step_mode_enable(confirm_state new_state) +{ + if(new_state == TRUE) + CRM->misc2_bit.auto_step_en = CRM_AUTO_STEP_MODE_ENABLE; + else + CRM->misc2_bit.auto_step_en = CRM_AUTO_STEP_MODE_DISABLE; +} + +/** + * @brief config hick divider select + * @param value + * this parameter can be one of the following values: + * - CRM_HICK48_DIV6 + * - CRM_HICK48_NODIV + * @retval none + */ +void crm_hick_divider_select(crm_hick_div_6_type value) +{ + CRM->misc1_bit.hickdiv = value; +} + +/** + * @brief hick as system clock frequency select + * @param value + * this parameter can be one of the following values: + * - CRM_HICK_SCLK_8MHZ + * - CRM_HICK_SCLK_48MHZ + * @retval none + */ +void crm_hick_sclk_frequency_select(crm_hick_sclk_frequency_type value) +{ + crm_hick_divider_select(CRM_HICK48_NODIV); + CRM->misc1_bit.hick_to_sclk = value; +} + +/** + * @brief usb 48 mhz clock source select + * @param value + * this parameter can be one of the following values: + * - CRM_USB_CLOCK_SOURCE_PLL + * - CRM_USB_CLOCK_SOURCE_HICK + * @retval none + */ +void crm_usb_clock_source_select(crm_usb_clock_source_type value) +{ + if(value == CRM_USB_CLOCK_SOURCE_HICK) + { + crm_hick_sclk_frequency_select(CRM_HICK_SCLK_48MHZ); + } + CRM->misc1_bit.hick_to_usb = value; +} + +/** + * @brief enable or disable clkout direct to tmr10 channel 1 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clkout_to_tmr10_enable(confirm_state new_state) +{ + CRM->misc2_bit.clk_to_tmr = new_state; +} + +/** + * @brief config crm pll + * pll_rcs_freq * pll_ns + * pll clock = -------------------------------- + * pll_ms * pll_fr_n + * attemtion: + * 31 <= pll_ns <= 500 + * 1 <= pll_ms <= 15 + * + * pll_rcs_freq + * 2mhz <= ---------------------- <= 16mhz + * pll_ms + * + * pll_rcs_freq * pll_ns + * 500mhz <= -------------------------------- <= 1000mhz + * pll_ms + * @param clock_source + * this parameter can be one of the following values: + * - CRM_PLL_SOURCE_HICK + * - CRM_PLL_SOURCE_HEXT + * @param pll_ns (31~500) + * @param pll_ms (1~15) + * @param pll_fr + * this parameter can be one of the following values: + * - CRM_PLL_FR_1 + * - CRM_PLL_FR_2 + * - CRM_PLL_FR_4 + * - CRM_PLL_FR_8 + * - CRM_PLL_FR_16 + * - CRM_PLL_FR_32 + * @retval none + */ +void crm_pll_config(crm_pll_clock_source_type clock_source, uint16_t pll_ns, \ + uint16_t pll_ms, crm_pll_fr_type pll_fr) +{ + /* config pll clock source */ + CRM->pllcfg_bit.pllrcs = clock_source; + + /* config pll multiplication factor */ + CRM->pllcfg_bit.pllns = pll_ns; + CRM->pllcfg_bit.pllms = pll_ms; + CRM->pllcfg_bit.pllfr = pll_fr; +} + +/** + * @brief select system clock source + * @param value + * this parameter can be one of the following values: + * - CRM_SCLK_HICK + * - CRM_SCLK_HEXT + * - CRM_SCLK_PLL + * @retval none + */ +void crm_sysclk_switch(crm_sclk_type value) +{ + CRM->cfg_bit.sclksel = value; +} + +/** + * @brief indicate which clock source is used as system clock + * @param none + * @retval crm_sclk + * this return can be one of the following values: + * - CRM_SCLK_HICK + * - CRM_SCLK_HEXT + * - CRM_SCLK_PLL + */ +crm_sclk_type crm_sysclk_switch_status_get(void) +{ + return (crm_sclk_type)CRM->cfg_bit.sclksts; +} + +/** + * @brief get crm clocks freqency + * @param clocks_struct + * - pointer to the crm_clocks_freq_type structure + * @retval none + */ +void crm_clocks_freq_get(crm_clocks_freq_type *clocks_struct) +{ + uint32_t pll_ns = 0, pll_ms = 0, pll_fr = 0, pll_clock_source = 0, pllrcsfreq = 0; + uint32_t temp = 0, div_value = 0; + crm_sclk_type sclk_source; + + static const uint8_t sclk_ahb_div_table[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + static const uint8_t ahb_apb1_div_table[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + static const uint8_t ahb_apb2_div_table[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + static const uint8_t pll_fr_table[6] = {1, 2, 4, 8, 16, 32}; + + /* get sclk source */ + sclk_source = crm_sysclk_switch_status_get(); + + switch(sclk_source) + { + case CRM_SCLK_HICK: + if(((CRM->misc1_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) + clocks_struct->sclk_freq = HICK_VALUE * 6; + else + clocks_struct->sclk_freq = HICK_VALUE; + break; + case CRM_SCLK_HEXT: + clocks_struct->sclk_freq = HEXT_VALUE; + break; + case CRM_SCLK_PLL: + /* get pll clock source */ + pll_clock_source = CRM->pllcfg_bit.pllrcs; + + /* get multiplication factor */ + pll_ns = CRM->pllcfg_bit.pllns; + pll_ms = CRM->pllcfg_bit.pllms; + pll_fr = pll_fr_table[CRM->pllcfg_bit.pllfr]; + + if (pll_clock_source == CRM_PLL_SOURCE_HICK) + { + /* hick selected as pll clock entry */ + pllrcsfreq = HICK_VALUE; + } + else + { + /* hext selected as pll clock entry */ + pllrcsfreq = HEXT_VALUE; + } + + clocks_struct->sclk_freq = (uint32_t)(((uint64_t)pllrcsfreq * pll_ns) / (pll_ms * pll_fr)); + break; + default: + clocks_struct->sclk_freq = HICK_VALUE; + break; + } + + /* compute sclk, ahbclk, abp1clk and apb2clk frequencies */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sclk_ahb_div_table[temp]; + /* ahbclk frequency */ + clocks_struct->ahb_freq = clocks_struct->sclk_freq >> div_value; + + /* get apb1 division */ + temp = CRM->cfg_bit.apb1div; + div_value = ahb_apb1_div_table[temp]; + /* apb1clk frequency */ + clocks_struct->apb1_freq = clocks_struct->ahb_freq >> div_value; + + /* get apb2 division */ + temp = CRM->cfg_bit.apb2div; + div_value = ahb_apb2_div_table[temp]; + /* apb2clk frequency */ + clocks_struct->apb2_freq = clocks_struct->ahb_freq >> div_value; +} + +/** + * @brief set crm clkout1 + * @param clkout + * this parameter can be one of the following values: + * - CRM_CLKOUT1_HICK + * - CRM_CLKOUT1_LEXT + * - CRM_CLKOUT1_HEXT + * - CRM_CLKOUT1_PLL + * @retval none + */ +void crm_clock_out1_set(crm_clkout1_select_type clkout) +{ + CRM->cfg_bit.clkout1_sel = clkout; +} + +/** + * @brief set crm clkout2 + * @param clkout + * this parameter can be one of the following values: + * - CRM_CLKOUT2_SCLK + * - CRM_CLKOUT2_HEXT + * - CRM_CLKOUT2_PLL + * - CRM_CLKOUT2_USB + * - CRM_CLKOUT2_ADC + * - CRM_CLKOUT2_HICK + * - CRM_CLKOUT2_LICK + * - CRM_CLKOUT2_LEXT + * @retval none + */ +void crm_clock_out2_set(crm_clkout2_select_type clkout) +{ + if(clkout < 0x10) + { + CRM->cfg_bit.clkout2_sel1 = (clkout & 0x3); + } + else + { + CRM->cfg_bit.clkout2_sel1 = 0x1; + CRM->misc1_bit.clkout2_sel2 = (clkout & 0xF); + } +} + +/** + * @brief set crm clkout1 division1 + * @param div1 + * this parameter can be one of the following values: + * - CRM_CLKOUT_INDEX_1 + * - CRM_CLKOUT_INDEX_2 + * @param div1 + * this parameter can be one of the following values: + * - CRM_CLKOUT_DIV1_1 + * - CRM_CLKOUT_DIV1_2 + * - CRM_CLKOUT_DIV1_3 + * - CRM_CLKOUT_DIV1_4 + * - CRM_CLKOUT_DIV1_5 + * @param div2 + * this parameter can be one of the following values: + * - CRM_CLKOUT_DIV2_1 + * - CRM_CLKOUT_DIV2_2 + * - CRM_CLKOUT_DIV2_4 + * - CRM_CLKOUT_DIV2_8 + * - CRM_CLKOUT_DIV2_16 + * - CRM_CLKOUT_DIV2_64 + * - CRM_CLKOUT_DIV2_128 + * - CRM_CLKOUT_DIV2_256 + * - CRM_CLKOUT_DIV2_512 + * @retval none + */ +void crm_clkout_div_set(crm_clkout_index_type index, crm_clkout_div1_type div1, crm_clkout_div2_type div2) +{ + if(index == CRM_CLKOUT_INDEX_1) + { + CRM->cfg_bit.clkout1div1 = div1; + CRM->misc1_bit.clkout1div2 = div2; + } + else + { + CRM->cfg_bit.clkout2div1 = div1; + CRM->misc1_bit.clkout2div2 = div2; + } +} + +/** + * @brief set emac output pulse width + * @param width + * this parameter can be one of the following values: + * - CRM_EMAC_PULSE_125MS + * - CRM_EMAC_PULSE_1SCLK + * @retval none + */ +void crm_emac_output_pulse_set(crm_emac_output_pulse_type width) +{ + CRM->misc2_bit.emac_pps_sel = width; +} + +/** + * @brief config crm interrupt + * @param int + * this parameter can be any combination of the following values: + * - CRM_LICK_STABLE_INT + * - CRM_LEXT_STABLE_INT + * - CRM_HICK_STABLE_INT + * - CRM_HEXT_STABLE_INT + * - CRM_PLL_STABLE_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_interrupt_enable(uint32_t crm_int, confirm_state new_state) +{ + if(TRUE == new_state) + CRM->clkint |= crm_int; + else + CRM->clkint &= ~crm_int; +} + +/** + * @brief calculate the pll parameters with pll reference clock and target pll output frequency. + * pll_rcs_freq * pll_ns + * pll clock = -------------------------------- + * pll_ms * pll_fr_n + * attemtion: + * 31 <= pll_ns <= 500 + * 1 <= pll_ms <= 15 + * + * pll_rcs_freq + * 2mhz <= ---------------------- <= 16mhz + * pll_ms + * + * pll_rcs_freq * pll_ns + * 500mhz <= -------------------------------- <= 1000mhz + * pll_ms + * @param pll_rcs + * this parameter can be one of the following values: + * - CRM_PLL_SOURCE_HICK + * - CRM_PLL_SOURCE_HEXT + * @param target_sclk_freq: target pll output frequency, such as 200 mhz (target_sclk_freq: 200000000) + * @param ret_ms: pointer to ms value, return the pll_ms of pll parameters + * @param ret_ns: pointer to ns value, return the pll_ns of pll parameters + * @param ret_fr: pointer to fr value, return the pll_fr of pll parameters + * @retval error_status (SUCCESS or ERROR) + */ +error_status crm_pll_parameter_calculate(crm_pll_clock_source_type pll_rcs, uint32_t target_sclk_freq, \ + uint16_t *ret_ms, uint16_t *ret_ns, uint16_t *ret_fr) +{ + uint32_t pll_rcs_freq = 0, ns = 0, ms = 0, fr = 0; + uint32_t ms_min = 0, ms_max = 0, error_min = 0xFFFFFFFF; + uint32_t result = 0, absolute_value = 0; + + /* reduce calculate accuracy, target_sclk_freq accuracy with khz */ + target_sclk_freq = target_sclk_freq / 1000; + + /* get pll reference clock frequency, accuracy with khz */ + if(pll_rcs == CRM_PLL_SOURCE_HICK) + pll_rcs_freq = HICK_VALUE / 1000; + else + pll_rcs_freq = HEXT_VALUE / 1000; + + /* polling ms range, accuracy with khz */ + for(ms = 1; ms <= 15; ms ++) + { + result = pll_rcs_freq / ms; + if((result >= 2000U) && (result <= 16000U)) + { + if(ms_min == 0) + ms_min = ms; + + ms_max = ms; + } + } + + /* polling pll parameters */ + for(ms = ms_min; ms <= ms_max; ms ++) + { + for(fr = 0; fr <= 5; fr ++) + { + for(ns = 31; ns <= 500; ns ++) + { + result = (pll_rcs_freq * ns) / (ms); + /* check vco frequency range, accuracy with khz */ + if((result < 500000U) || (result > 1000000U)) + { + continue; + } + /* calculate pll output frequency */ + result = result / (0x1 << fr); + /* check frequency */ + if(target_sclk_freq == result) + { + *ret_ms = ms; + *ret_ns = ns; + *ret_fr = fr; + /* the pll parameters that is equal to target_sclk_freq */ + return SUCCESS; + } + /* calculate error range, accuracy with khz */ + absolute_value = (result > target_sclk_freq) ? (result - target_sclk_freq) : (target_sclk_freq - result); + if(absolute_value < error_min) + { + error_min = absolute_value; + *ret_ms = ms; + *ret_ns = ns; + *ret_fr = fr; + } + } + } + } + /* the pll parameters that is the closest approach to target_sclk_freq */ + return ERROR; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c new file mode 100644 index 0000000000..3d90ff4d59 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c @@ -0,0 +1,454 @@ +/** + ************************************************************************** + * @file at32f435_437_dac.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dac firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +#ifdef DAC_MODULE_ENABLED + +/** @defgroup DAC_private_functions + * @{ + */ + +/** + * @brief dac reset + * @param none + * @retval none + */ +void dac_reset(void) +{ + crm_periph_reset(CRM_DAC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_DAC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable dac + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1en = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2en = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac output buffer + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_output_buffer_enable(dac_select_type dac_select, confirm_state new_state) +{ + new_state = (confirm_state)!new_state; + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1obdis = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2obdis = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_trigger_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1trgen = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2trgen = new_state; + break; + default: + break; + } +} + +/** + * @brief select dac trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_trigger_source + * this parameter can be one of the following values: + * - DAC_TMR6_TRGOUT_EVENT + * - DAC_TMR8_TRGOUT_EVENT + * - DAC_TMR7_TRGOUT_EVENT + * - DAC_TMR5_TRGOUT_EVENT + * - DAC_TMR2_TRGOUT_EVENT + * - DAC_TMR4_TRGOUT_EVENT + * - DAC_EXTERNAL_INTERRUPT_LINE_9 + * - DAC_SOFTWARE_TRIGGER + * @retval none + */ +void dac_trigger_select(dac_select_type dac_select, dac_trigger_type dac_trigger_source) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1trgsel = dac_trigger_source; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2trgsel = dac_trigger_source; + break; + default: + break; + } +} + +/** + * @brief generate dac software trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval none + */ +void dac_software_trigger_generate(dac_select_type dac_select) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->swtrg_bit.d1swtrg = TRUE; + break; + case DAC2_SELECT: + DAC->swtrg_bit.d2swtrg = TRUE; + break; + default: + break; + } +} + +/** + * @brief generate dac dual software trigger synchronously + * @param none + * @retval none + */ +void dac_dual_software_trigger_generate(void) +{ + DAC->swtrg |= 0x03; +} + +/** + * @brief generate dac wave + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_wave + * this parameter can be one of the following values: + * - DAC_WAVE_GENERATE_NONE + * - DAC_WAVE_GENERATE_NOISE + * - DAC_WAVE_GENERATE_TRIANGLE + * @retval none + */ +void dac_wave_generate(dac_select_type dac_select, dac_wave_type dac_wave) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1nm = dac_wave; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2nm = dac_wave; + break; + default: + break; + } +} + +/** + * @brief select dac mask amplitude + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_mask_amplitude + * this parameter can be one of the following values: + * - DAC_LSFR_BIT0_AMPLITUDE_1 + * - DAC_LSFR_BIT10_AMPLITUDE_3 + * - DAC_LSFR_BIT20_AMPLITUDE_7 + * - DAC_LSFR_BIT30_AMPLITUDE_15 + * - DAC_LSFR_BIT40_AMPLITUDE_31 + * - DAC_LSFR_BIT50_AMPLITUDE_63 + * - DAC_LSFR_BIT60_AMPLITUDE_127 + * - DAC_LSFR_BIT70_AMPLITUDE_255 + * - DAC_LSFR_BIT80_AMPLITUDE_511 + * - DAC_LSFR_BIT90_AMPLITUDE_1023 + * - DAC_LSFR_BITA0_AMPLITUDE_2047 + * - DAC_LSFR_BITB0_AMPLITUDE_4095 + * @retval none + */ +void dac_mask_amplitude_select(dac_select_type dac_select, dac_mask_amplitude_type dac_mask_amplitude) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1nbsel = dac_mask_amplitude; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2nbsel = dac_mask_amplitude; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac dma + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_dma_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1dmaen = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2dmaen = new_state; + break; + default: + break; + } +} + +/** + * @brief get dac data output + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval dac channel data output + */ +uint16_t dac_data_output_get(dac_select_type dac_select) +{ + uint16_t data_output =0; + switch(dac_select) + { + case DAC1_SELECT: + data_output = DAC->d1odt_bit.d1odt; + break; + case DAC2_SELECT: + data_output = DAC->d2odt_bit.d2odt; + break; + default: + break; + } + return data_output; +} + +/** + * @brief set dac1 data + * @param dac1_aligned + * this parameter can be one of the following values: + * DAC1_12BIT_RIGHT + * DAC1_12BIT_LEFT + * DAC1_8BIT_RIGHT + * @param dac1_data :indecate from selected data holding register + * @retval none + */ +void dac_1_data_set(dac1_aligned_data_type dac1_aligned, uint16_t dac1_data) +{ + *(__IO uint32_t *) dac1_aligned = dac1_data; +} + +/** + * @brief set dac2 data + * @param dac2_aligned + * this parameter can be one of the following values: + * DAC2_12BIT_RIGHT + * DAC2_12BIT_LEFT + * DAC2_8BIT_RIGHT + * @param dac2_data :indecate from selected data holding register + * @retval none + */ +void dac_2_data_set(dac2_aligned_data_type dac2_aligned, uint16_t dac2_data) +{ + *(__IO uint32_t *) dac2_aligned = dac2_data; +} + +/** + * @brief set dac dual data + * @param dac_dual + * this parameter can be one of the following values: + * DAC_DUAL_12BIT_RIGHT + * DAC_DUAL_12BIT_LEFT + * DAC_DUAL_8BIT_RIGHT + * @param data1 :dac1 channel indecate from selected data holding register + * @param data2 :dac1 channel indecate from selected data holding register + * @retval none + */ +void dac_dual_data_set(dac_dual_data_type dac_dual, uint16_t data1, uint16_t data2) +{ + switch(dac_dual) + { + case DAC_DUAL_12BIT_RIGHT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 16)); + break; + case DAC_DUAL_12BIT_LEFT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 16)); + break; + case DAC_DUAL_8BIT_RIGHT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 8)); + break; + default: + break; + } +} + +/** + * @brief enable/disable dac dma udr interrupt + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_udr_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1dmaudrien = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2dmaudrien = new_state; + break; + default: + break; + } +} + +/** + * @brief get flag of the dac udr flag. + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval the new state of dac udr flag status(SET or RESET). + */ +flag_status dac_udr_flag_get(dac_select_type dac_select) +{ + flag_status status = RESET; + + switch(dac_select) + { + case DAC1_SELECT: + if(DAC->sts_bit.d1dmaudrf != 0) + status = SET; + break; + case DAC2_SELECT: + if(DAC->sts_bit.d2dmaudrf != 0) + status = SET; + break; + default: + break; + } + return status; +} + +/** + * @brief clear the dac udr flag. + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval none + */ +void dac_udr_flag_clear(dac_select_type dac_select) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->sts = DAC1_D1DMAUDRF; + break; + case DAC2_SELECT: + DAC->sts = DAC2_D2DMAUDRF; + break; + default: + break; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c new file mode 100644 index 0000000000..bb451a7c23 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c @@ -0,0 +1,135 @@ +/** + ************************************************************************** + * @file at32f435_437_mcudbg.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the mcudbg firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DEBUG + * @brief DEBUG driver modules + * @{ + */ + +#ifdef DEBUG_MODULE_ENABLED + +/** @defgroup DEBUG_private_functions + * @{ + */ + +/** + * @brief get debug device id + * @param none + * @retval the debug device id + */ +uint32_t debug_device_id_get(void) +{ + return DEBUGMCU->pid; +} +/** + * @brief set periph debug mode + * @param periph_debug_mode + * this parameter can be one of the following values: + * - DEBUG_SLEEP + * - DEBUG_DEEPSLEEP + * - DEBUG_STANDBY + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_low_power_mode_set(uint32_t low_power_mode, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->ctrl |= low_power_mode; + } + else + { + DEBUGMCU->ctrl &= ~low_power_mode; + } +} +/** + * @brief set apb1 periph debug mode + * @param periph_debug_mode + * this parameter can be any combination of the following values: + * - DEBUG_TMR2_PAUSE - DEBUG_TMR3_PAUSE + * - DEBUG_TMR4_PAUSE - DEBUG_TMR5_PAUSE + * - DEBUG_TMR6_PAUSE - DEBUG_TMR7_PAUSE + * - DEBUG_TMR12_PAUSE - DEBUG_TMR13_PAUSE + * - DEBUG_TMR14_PAUSE - DEBUG_ERTC_PAUSE + * - DEBUG_WWDT_PAUSE - DEBUG_WDT_PAUSE + * - DEBUG_ERTC_512_PAUSE - DEBUG_I2C1_SMBUS_TIMEOUT + * - DEBUG_I2C2_SMBUS_TIMEOUT - DEBUG_I2C3_SMBUS_TIMEOUT + * - DEBUG_CAN1_PAUSE - DEBUG_CAN2_PAUSE + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_apb1_periph_mode_set(uint32_t apb1_periph, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->apb1_frz |= apb1_periph; + } + else + { + DEBUGMCU->apb1_frz &= ~apb1_periph; + } +} +/** + * @brief set apb2 periph debug mode + * @param periph_debug_mode + * this parameter can be any combination of the following values: + * - DEBUG_TMR1_PAUSE - DEBUG_TMR8_PAUSE + * - DEBUG_TMR20_PAUSE - DEBUG_TMR9_PAUSE + * - DEBUG_TMR10_PAUSE - DEBUG_TMR11_PAUSE + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_apb2_periph_mode_set(uint32_t apb2_periph, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->apb2_frz |= apb2_periph; + } + else + { + DEBUGMCU->apb2_frz &= ~apb2_periph; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c new file mode 100644 index 0000000000..a7d0313d85 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c @@ -0,0 +1,683 @@ +/** + ************************************************************************** + * @file at32f435_437_dma.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dma firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +#ifdef DMA_MODULE_ENABLED + +/** @defgroup DMA_private_functions + * @{ + */ + +/** + * @brief reset dmax channely register. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @retval none. + */ +void dma_reset(dma_channel_type *dmax_channely) +{ + uint32_t temp = 0; + dmax_channely->ctrl_bit.chen = FALSE; + dmax_channely->ctrl = 0; + dmax_channely->dtcnt = 0; + dmax_channely->paddr = 0; + dmax_channely->maddr = 0; + + temp = (uint32_t)dmax_channely; + + if((temp & 0x6FF) < 0x608) + { + /* dma1 channel */ + DMA1->clr |= (uint32_t)(0x0F << ((((temp & 0xFF) - 0x08) / 0x14) * 4)); + } + else if((temp & 0x6FF) < 0x688) + { + /* dma2 channel */ + DMA2->clr |= (uint32_t)(0x0F << ((((temp & 0xFF) - 0x08) / 0x14) * 4)); + } +} + +/** + * @brief set the number of data to be transferred. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param data_number: the number of data to be transferred (0x0000~0xFFFF). + * @retval none. + */ +void dma_data_number_set(dma_channel_type *dmax_channely, uint16_t data_number) +{ + dmax_channely->dtcnt = data_number; +} + +/** + * @brief get the number of data to be transferred. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @retval the number value. + */ +uint16_t dma_data_number_get(dma_channel_type *dmax_channely) +{ + return (uint16_t)dmax_channely->dtcnt; +} + +/** + * @brief enable or disable dma interrupt. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param dma_int: + * this parameter can be any combination of the following values: + * - DMA_FDT_INT + * - DMA_HDT_INT + * - DMA_DTERR_INT + * @param new_state (TRUE or FALSE) + * @retval none. + */ +void dma_interrupt_enable(dma_channel_type *dmax_channely, uint32_t dma_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmax_channely->ctrl |= dma_int; + } + else + { + dmax_channely->ctrl &= ~dma_int; + } +} + +/** + * @brief enable or disable dma channel. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dma_channel_enable(dma_channel_type *dmax_channely, confirm_state new_state) +{ + dmax_channely->ctrl_bit.chen = new_state; +} + +/** + * @brief dma flag get. + * @param dma_flag + * - DMA1_GL1_FLAG - DMA1_FDT1_FLAG - DMA1_HDT1_FLAG - DMA1_DTERR1_FLAG + * - DMA1_GL2_FLAG - DMA1_FDT2_FLAG - DMA1_HDT2_FLAG - DMA1_DTERR2_FLAG + * - DMA1_GL3_FLAG - DMA1_FDT3_FLAG - DMA1_HDT3_FLAG - DMA1_DTERR3_FLAG + * - DMA1_GL4_FLAG - DMA1_FDT4_FLAG - DMA1_HDT4_FLAG - DMA1_DTERR4_FLAG + * - DMA1_GL5_FLAG - DMA1_FDT5_FLAG - DMA1_HDT5_FLAG - DMA1_DTERR5_FLAG + * - DMA1_GL6_FLAG - DMA1_FDT6_FLAG - DMA1_HDT6_FLAG - DMA1_DTERR6_FLAG + * - DMA1_GL7_FLAG - DMA1_FDT7_FLAG - DMA1_HDT7_FLAG - DMA1_DTERR7_FLAG + * - DMA2_GL1_FLAG - DMA2_FDT1_FLAG - DMA2_HDT1_FLAG - DMA2_DTERR1_FLAG + * - DMA2_GL2_FLAG - DMA2_FDT2_FLAG - DMA2_HDT2_FLAG - DMA2_DTERR2_FLAG + * - DMA2_GL3_FLAG - DMA2_FDT3_FLAG - DMA2_HDT3_FLAG - DMA2_DTERR3_FLAG + * - DMA2_GL4_FLAG - DMA2_FDT4_FLAG - DMA2_HDT4_FLAG - DMA2_DTERR4_FLAG + * - DMA2_GL5_FLAG - DMA2_FDT5_FLAG - DMA2_HDT5_FLAG - DMA2_DTERR5_FLAG + * - DMA2_GL6_FLAG - DMA2_FDT6_FLAG - DMA2_HDT6_FLAG - DMA2_DTERR6_FLAG + * - DMA2_GL7_FLAG - DMA2_FDT7_FLAG - DMA2_HDT7_FLAG - DMA2_DTERR7_FLAG + * @retval state of dma flag. + */ +flag_status dma_flag_get(uint32_t dmax_flag) +{ + uint32_t temp = 0; + + if(dmax_flag > 0x10000000) + { + temp = DMA2->sts; + } + else + { + temp = DMA1->sts; + } + + if((temp & dmax_flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dma flag clear. + * @param dma_flag + * this parameter can be one of the following values: + * - DMA1_GL1_FLAG - DMA1_FDT1_FLAG - DMA1_HDT1_FLAG - DMA1_DTERR1_FLAG + * - DMA1_GL2_FLAG - DMA1_FDT2_FLAG - DMA1_HDT2_FLAG - DMA1_DTERR2_FLAG + * - DMA1_GL3_FLAG - DMA1_FDT3_FLAG - DMA1_HDT3_FLAG - DMA1_DTERR3_FLAG + * - DMA1_GL4_FLAG - DMA1_FDT4_FLAG - DMA1_HDT4_FLAG - DMA1_DTERR4_FLAG + * - DMA1_GL5_FLAG - DMA1_FDT5_FLAG - DMA1_HDT5_FLAG - DMA1_DTERR5_FLAG + * - DMA1_GL6_FLAG - DMA1_FDT6_FLAG - DMA1_HDT6_FLAG - DMA1_DTERR6_FLAG + * - DMA1_GL7_FLAG - DMA1_FDT7_FLAG - DMA1_HDT7_FLAG - DMA1_DTERR7_FLAG + * - DMA2_GL1_FLAG - DMA2_FDT1_FLAG - DMA2_HDT1_FLAG - DMA2_DTERR1_FLAG + * - DMA2_GL2_FLAG - DMA2_FDT2_FLAG - DMA2_HDT2_FLAG - DMA2_DTERR2_FLAG + * - DMA2_GL3_FLAG - DMA2_FDT3_FLAG - DMA2_HDT3_FLAG - DMA2_DTERR3_FLAG + * - DMA2_GL4_FLAG - DMA2_FDT4_FLAG - DMA2_HDT4_FLAG - DMA2_DTERR4_FLAG + * - DMA2_GL5_FLAG - DMA2_FDT5_FLAG - DMA2_HDT5_FLAG - DMA2_DTERR5_FLAG + * - DMA2_GL6_FLAG - DMA2_FDT6_FLAG - DMA2_HDT6_FLAG - DMA2_DTERR6_FLAG + * - DMA2_GL7_FLAG - DMA2_FDT7_FLAG - DMA2_HDT7_FLAG - DMA2_DTERR7_FLAG + * @retval none. + */ +void dma_flag_clear(uint32_t dmax_flag) +{ + if(dmax_flag > ((uint32_t)0x10000000)) + { + DMA2->clr = (uint32_t)(dmax_flag & 0x0FFFFFFF); + } + else + { + DMA1->clr = dmax_flag; + } +} + +/** + * @brief dma init config with its default value. + * @param dma_init_struct: pointer to a dma_init_type structure which will be initialized. + * @retval none. + */ +void dma_default_para_init(dma_init_type *dma_init_struct) +{ + dma_init_struct->peripheral_base_addr = 0; + dma_init_struct->memory_base_addr = 0; + dma_init_struct->direction = DMA_DIR_PERIPHERAL_TO_MEMORY; + dma_init_struct->buffer_size = 0; + dma_init_struct->peripheral_inc_enable = FALSE; + dma_init_struct->memory_inc_enable = FALSE; + dma_init_struct->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE; + dma_init_struct->memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + dma_init_struct->loop_mode_enable = FALSE; + dma_init_struct->priority = DMA_PRIORITY_LOW; +} + +/** + * @brief dma init. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param dma_init_struct: pointer to a dma_init_type structure. + * @retval none. + */ +void dma_init(dma_channel_type *dmax_channely, dma_init_type *dma_init_struct) +{ + /* clear ctrl register dtd bit and m2m bit */ + dmax_channely->ctrl &= 0xbfef; + dmax_channely->ctrl |= dma_init_struct->direction; + + dmax_channely->ctrl_bit.chpl = dma_init_struct->priority; + dmax_channely->ctrl_bit.mwidth = dma_init_struct->memory_data_width; + dmax_channely->ctrl_bit.pwidth = dma_init_struct->peripheral_data_width; + dmax_channely->ctrl_bit.mincm = dma_init_struct->memory_inc_enable; + dmax_channely->ctrl_bit.pincm = dma_init_struct->peripheral_inc_enable; + dmax_channely->ctrl_bit.lm = dma_init_struct->loop_mode_enable; + dmax_channely->dtcnt_bit.cnt = dma_init_struct->buffer_size; + dmax_channely->paddr = dma_init_struct->peripheral_base_addr; + dmax_channely->maddr = dma_init_struct->memory_base_addr; +} +/** + * @brief dmamux init. + * @param dma_x: pointer to a dma_type structure, can be DMA1 or DMA2. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_req_sel: + * this parameter can be one of the following values: + * - DMAMUX_DMAREQ_ID_REQ_G1 - DMAMUX_DMAREQ_ID_REQ_G2 - DMAMUX_DMAREQ_ID_REQ_G3 - DMAMUX_DMAREQ_ID_REQ_G4 + * - DMAMUX_DMAREQ_ID_ADC1 - DMAMUX_DMAREQ_ID_ADC2 - DMAMUX_DMAREQ_ID_ADC3 - DMAMUX_DMAREQ_ID_DAC1 + * - DMAMUX_DMAREQ_ID_DAC2 - DMAMUX_DMAREQ_ID_TMR6_OVERFLOW- DMAMUX_DMAREQ_ID_TMR7_OVERFLOW- DMAMUX_DMAREQ_ID_SPI1_RX + * - DMAMUX_DMAREQ_ID_SPI1_TX - DMAMUX_DMAREQ_ID_SPI2_RX - DMAMUX_DMAREQ_ID_SPI2_TX - DMAMUX_DMAREQ_ID_SPI3_RX + * - DMAMUX_DMAREQ_ID_SPI3_TX - DMAMUX_DMAREQ_ID_SPI4_RX - DMAMUX_DMAREQ_ID_SPI4_TX - DMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - DMAMUX_DMAREQ_ID_I2S2_EXT_TX - DMAMUX_DMAREQ_ID_I2S3_EXT_RX - DMAMUX_DMAREQ_ID_I2S3_EXT_TX - DMAMUX_DMAREQ_ID_I2C1_RX + * - DMAMUX_DMAREQ_ID_I2C1_TX - DMAMUX_DMAREQ_ID_I2C2_RX - DMAMUX_DMAREQ_ID_I2C2_TX - DMAMUX_DMAREQ_ID_I2C3_RX + * - DMAMUX_DMAREQ_ID_I2C3_TX - DMAMUX_DMAREQ_ID_USART1_RX - DMAMUX_DMAREQ_ID_USART1_TX - DMAMUX_DMAREQ_ID_USART2_RX + * - DMAMUX_DMAREQ_ID_USART2_TX - DMAMUX_DMAREQ_ID_USART3_RX - DMAMUX_DMAREQ_ID_USART3_TX - DMAMUX_DMAREQ_ID_UART4_RX + * - DMAMUX_DMAREQ_ID_UART4_TX - DMAMUX_DMAREQ_ID_UART5_RX - DMAMUX_DMAREQ_ID_UART5_TX - DMAMUX_DMAREQ_ID_USART6_RX + * - DMAMUX_DMAREQ_ID_USART6_TX - DMAMUX_DMAREQ_ID_UART7_RX - DMAMUX_DMAREQ_ID_UART7_TX - DMAMUX_DMAREQ_ID_UART8_RX + * - DMAMUX_DMAREQ_ID_UART8_TX - DMAMUX_DMAREQ_ID_SDIO1 - DMAMUX_DMAREQ_ID_SDIO2 - DMAMUX_DMAREQ_ID_QSPI1 + * - DMAMUX_DMAREQ_ID_QSPI2 - DMAMUX_DMAREQ_ID_TMR1_CH1 - DMAMUX_DMAREQ_ID_TMR1_CH2 - DMAMUX_DMAREQ_ID_TMR1_CH3 + * - DMAMUX_DMAREQ_ID_TMR1_CH4 - DMAMUX_DMAREQ_ID_TMR1_OVERFLOW- DMAMUX_DMAREQ_ID_TMR1_TRIG - DMAMUX_DMAREQ_ID_TMR1_COM + * - DMAMUX_DMAREQ_ID_TMR8_CH1 - DMAMUX_DMAREQ_ID_TMR8_CH2 - DMAMUX_DMAREQ_ID_TMR8_CH3 - DMAMUX_DMAREQ_ID_TMR8_CH4 + * - DMAMUX_DMAREQ_ID_TMR8_UP - DMAMUX_DMAREQ_ID_TMR8_TRIG - DMAMUX_DMAREQ_ID_TMR8_COM - DMAMUX_DMAREQ_ID_TMR2_CH1 + * - DMAMUX_DMAREQ_ID_TMR2_CH2 - DMAMUX_DMAREQ_ID_TMR2_CH3 - DMAMUX_DMAREQ_ID_TMR2_CH4 - DMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR2_TRIG - DMAMUX_DMAREQ_ID_TMR3_CH1 - DMAMUX_DMAREQ_ID_TMR3_CH2 - DMAMUX_DMAREQ_ID_TMR3_CH3 + * - DMAMUX_DMAREQ_ID_TMR3_CH4 - DMAMUX_DMAREQ_ID_TMR3_OVERFLOW- DMAMUX_DMAREQ_ID_TMR3_TRIG - DMAMUX_DMAREQ_ID_TMR4_CH1 + * - DMAMUX_DMAREQ_ID_TMR4_CH2 - DMAMUX_DMAREQ_ID_TMR4_CH3 - DMAMUX_DMAREQ_ID_TMR4_CH4 - DMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR4_TRIG - DMAMUX_DMAREQ_ID_TMR5_CH1 - DMAMUX_DMAREQ_ID_TMR5_CH2 - DMAMUX_DMAREQ_ID_TMR5_CH3 + * - DMAMUX_DMAREQ_ID_TMR5_CH4 - DMAMUX_DMAREQ_ID_TMR5_OVERFLOW- DMAMUX_DMAREQ_ID_TMR5_TRIG - DMAMUX_DMAREQ_ID_TMR20_CH1 + * - DMAMUX_DMAREQ_ID_TMR20_CH2 - DMAMUX_DMAREQ_ID_TMR20_CH3 - DMAMUX_DMAREQ_ID_TMR20_CH4 - DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR20_TRIG - DMAMUX_DMAREQ_ID_TMR20_HALL - DMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void dma_flexible_config(dma_type* dma_x, dmamux_channel_type *dmamux_channelx, dmamux_requst_id_sel_type dmamux_req_sel) +{ + dma_x->muxsel_bit.tblsel = TRUE; + dmamux_channelx->muxctrl_bit.reqsel = dmamux_req_sel; +} + +/** + * @brief enable or disable the dmamux. + * @param dma_x: pointer to a dma_type structure, can be DMA1 or DMA2. + * @param new_state (TRUE or FALSE) . + * @retval none. + */ +void dmamux_enable(dma_type *dma_x, confirm_state new_state) +{ + dma_x->muxsel_bit.tblsel = new_state; +} + +/** + * @brief dmamux init. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_req_sel: + * this parameter can be one of the following values: + * - DMAMUX_DMAREQ_ID_REQ_G1 - DMAMUX_DMAREQ_ID_REQ_G2 - DMAMUX_DMAREQ_ID_REQ_G3 - DMAMUX_DMAREQ_ID_REQ_G4 + * - DMAMUX_DMAREQ_ID_ADC1 - DMAMUX_DMAREQ_ID_ADC2 - DMAMUX_DMAREQ_ID_ADC3 - DMAMUX_DMAREQ_ID_DAC1 + * - DMAMUX_DMAREQ_ID_DAC2 - DMAMUX_DMAREQ_ID_TMR6_OVERFLOW- DMAMUX_DMAREQ_ID_TMR7_OVERFLOW- DMAMUX_DMAREQ_ID_SPI1_RX + * - DMAMUX_DMAREQ_ID_SPI1_TX - DMAMUX_DMAREQ_ID_SPI2_RX - DMAMUX_DMAREQ_ID_SPI2_TX - DMAMUX_DMAREQ_ID_SPI3_RX + * - DMAMUX_DMAREQ_ID_SPI3_TX - DMAMUX_DMAREQ_ID_SPI4_RX - DMAMUX_DMAREQ_ID_SPI4_TX - DMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - DMAMUX_DMAREQ_ID_I2S2_EXT_TX - DMAMUX_DMAREQ_ID_I2S3_EXT_RX - DMAMUX_DMAREQ_ID_I2S3_EXT_TX - DMAMUX_DMAREQ_ID_I2C1_RX + * - DMAMUX_DMAREQ_ID_I2C1_TX - DMAMUX_DMAREQ_ID_I2C2_RX - DMAMUX_DMAREQ_ID_I2C2_TX - DMAMUX_DMAREQ_ID_I2C3_RX + * - DMAMUX_DMAREQ_ID_I2C3_TX - DMAMUX_DMAREQ_ID_USART1_RX - DMAMUX_DMAREQ_ID_USART1_TX - DMAMUX_DMAREQ_ID_USART2_RX + * - DMAMUX_DMAREQ_ID_USART2_TX - DMAMUX_DMAREQ_ID_USART3_RX - DMAMUX_DMAREQ_ID_USART3_TX - DMAMUX_DMAREQ_ID_UART4_RX + * - DMAMUX_DMAREQ_ID_UART4_TX - DMAMUX_DMAREQ_ID_UART5_RX - DMAMUX_DMAREQ_ID_UART5_TX - DMAMUX_DMAREQ_ID_USART6_RX + * - DMAMUX_DMAREQ_ID_USART6_TX - DMAMUX_DMAREQ_ID_UART7_RX - DMAMUX_DMAREQ_ID_UART7_TX - DMAMUX_DMAREQ_ID_UART8_RX + * - DMAMUX_DMAREQ_ID_UART8_TX - DMAMUX_DMAREQ_ID_SDIO1 - DMAMUX_DMAREQ_ID_SDIO2 - DMAMUX_DMAREQ_ID_QSPI1 + * - DMAMUX_DMAREQ_ID_QSPI2 - DMAMUX_DMAREQ_ID_TMR1_CH1 - DMAMUX_DMAREQ_ID_TMR1_CH2 - DMAMUX_DMAREQ_ID_TMR1_CH3 + * - DMAMUX_DMAREQ_ID_TMR1_CH4 - DMAMUX_DMAREQ_ID_TMR1_OVERFLOW- DMAMUX_DMAREQ_ID_TMR1_TRIG - DMAMUX_DMAREQ_ID_TMR1_COM + * - DMAMUX_DMAREQ_ID_TMR8_CH1 - DMAMUX_DMAREQ_ID_TMR8_CH2 - DMAMUX_DMAREQ_ID_TMR8_CH3 - DMAMUX_DMAREQ_ID_TMR8_CH4 + * - DMAMUX_DMAREQ_ID_TMR8_UP - DMAMUX_DMAREQ_ID_TMR8_TRIG - DMAMUX_DMAREQ_ID_TMR8_COM - DMAMUX_DMAREQ_ID_TMR2_CH1 + * - DMAMUX_DMAREQ_ID_TMR2_CH2 - DMAMUX_DMAREQ_ID_TMR2_CH3 - DMAMUX_DMAREQ_ID_TMR2_CH4 - DMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR2_TRIG - DMAMUX_DMAREQ_ID_TMR3_CH1 - DMAMUX_DMAREQ_ID_TMR3_CH2 - DMAMUX_DMAREQ_ID_TMR3_CH3 + * - DMAMUX_DMAREQ_ID_TMR3_CH4 - DMAMUX_DMAREQ_ID_TMR3_OVERFLOW- DMAMUX_DMAREQ_ID_TMR3_TRIG - DMAMUX_DMAREQ_ID_TMR4_CH1 + * - DMAMUX_DMAREQ_ID_TMR4_CH2 - DMAMUX_DMAREQ_ID_TMR4_CH3 - DMAMUX_DMAREQ_ID_TMR4_CH4 - DMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR4_TRIG - DMAMUX_DMAREQ_ID_TMR5_CH1 - DMAMUX_DMAREQ_ID_TMR5_CH2 - DMAMUX_DMAREQ_ID_TMR5_CH3 + * - DMAMUX_DMAREQ_ID_TMR5_CH4 - DMAMUX_DMAREQ_ID_TMR5_OVERFLOW- DMAMUX_DMAREQ_ID_TMR5_TRIG - DMAMUX_DMAREQ_ID_TMR20_CH1 + * - DMAMUX_DMAREQ_ID_TMR20_CH2 - DMAMUX_DMAREQ_ID_TMR20_CH3 - DMAMUX_DMAREQ_ID_TMR20_CH4 - DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR20_TRIG - DMAMUX_DMAREQ_ID_TMR20_HALL - DMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void dmamux_init(dmamux_channel_type *dmamux_channelx, dmamux_requst_id_sel_type dmamux_req_sel) +{ + dmamux_channelx->muxctrl_bit.reqsel = dmamux_req_sel; +} + +/** + * @brief dmamux sync init struct config with its default value. + * @param dmamux_sync_init_struct: pointer to a dmamux_sync_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_sync_default_para_init(dmamux_sync_init_type *dmamux_sync_init_struct) +{ + dmamux_sync_init_struct->sync_enable = FALSE; + dmamux_sync_init_struct->sync_event_enable = FALSE; + dmamux_sync_init_struct->sync_polarity = DMAMUX_SYNC_POLARITY_DISABLE; + dmamux_sync_init_struct->sync_request_number = 0x0; + dmamux_sync_init_struct->sync_signal_sel = (dmamux_sync_id_sel_type)0; +} + +/** + * @brief dmamux synchronization config. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_sync_init_struct: ointer to a dmamux_sync_init_type structure. + * @retval none. + */ +void dmamux_sync_config(dmamux_channel_type *dmamux_channelx, dmamux_sync_init_type *dmamux_sync_init_struct) +{ + dmamux_channelx->muxctrl_bit.syncsel = dmamux_sync_init_struct->sync_signal_sel; + dmamux_channelx->muxctrl_bit.syncpol = dmamux_sync_init_struct->sync_polarity; + dmamux_channelx->muxctrl_bit.reqcnt = dmamux_sync_init_struct->sync_request_number; + dmamux_channelx->muxctrl_bit.evtgen = dmamux_sync_init_struct->sync_event_enable; + dmamux_channelx->muxctrl_bit.syncen = dmamux_sync_init_struct->sync_enable; +} + +/** + * @brief dmamux request generator init struct config with its default value. + * @param dmamux_gen_init_struct: pointer to a dmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_generator_default_para_init(dmamux_gen_init_type *dmamux_gen_init_struct) +{ + dmamux_gen_init_struct->gen_enable = FALSE; + dmamux_gen_init_struct->gen_polarity = DMAMUX_GEN_POLARITY_DISABLE; + dmamux_gen_init_struct->gen_request_number = 0x0; + dmamux_gen_init_struct->gen_signal_sel = (dmamux_gen_id_sel_type)0x0; +} + +/** + * @brief dmamux request generator init. + * @param dmamux_gen_x : + * this parameter can be one of the following values: + * - DMA1MUX_GENERATOR1 + * - DMA1MUX_GENERATOR2 + * - DMA1MUX_GENERATOR3 + * - DMA1MUX_GENERATOR4 + * - DMA2MUX_GENERATOR1 + * - DMA2MUX_GENERATOR2 + * - DMA2MUX_GENERATOR3 + * - DMA2MUX_GENERATOR4 + * @param dmamux_gen_init_struct: pointer to a dmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_generator_config(dmamux_generator_type *dmamux_gen_x, dmamux_gen_init_type *dmamux_gen_init_struct) +{ + dmamux_gen_x->gctrl_bit.sigsel = dmamux_gen_init_struct->gen_signal_sel; + dmamux_gen_x->gctrl_bit.gpol = dmamux_gen_init_struct->gen_polarity; + dmamux_gen_x->gctrl_bit.greqcnt = dmamux_gen_init_struct->gen_request_number; + dmamux_gen_x->gctrl_bit.gen = dmamux_gen_init_struct->gen_enable; +} + +/** + * @brief enable or disable the dmamux sync interrupts. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dmamux_sync_interrupt_enable(dmamux_channel_type *dmamux_channelx, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmamux_channelx->muxctrl_bit.syncovien = TRUE; + } + else + { + dmamux_channelx->muxctrl_bit.syncovien = FALSE; + } +} + +/** + * @brief enable or disable the dmamux request generator interrupts. + * @param dmamux_gen_x : pointer to a dmamux_generator_type structure. + * this parameter can be one of the following values: + * - DMA1MUX_GENERATOR1 + * - DMA1MUX_GENERATOR2 + * - DMA1MUX_GENERATOR3 + * - DMA1MUX_GENERATOR4 + * - DMA2MUX_GENERATOR1 + * - DMA2MUX_GENERATOR2 + * - DMA2MUX_GENERATOR3 + * - DMA2MUX_GENERATOR4 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dmamux_generator_interrupt_enable(dmamux_generator_type *dmamux_gen_x, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmamux_gen_x->gctrl_bit.trgovien = TRUE; + } + else + { + dmamux_gen_x->gctrl_bit.trgovien = FALSE; + } +} + +/** + * @brief dmamux sync flag get. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_SYNC_OV1_FLAG + * - DMAMUX_SYNC_OV2_FLAG + * - DMAMUX_SYNC_OV3_FLAG + * - DMAMUX_SYNC_OV4_FLAG + * - DMAMUX_SYNC_OV5_FLAG + * - DMAMUX_SYNC_OV6_FLAG + * - DMAMUX_SYNC_OV7_FLAG + * @retval state of dmamux sync flag. + */ +flag_status dmamux_sync_flag_get(dma_type *dma_x, uint32_t flag) +{ + if((dma_x->muxsyncsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dmamux sync flag clear. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_SYNC_OV1_FLAG + * - DMAMUX_SYNC_OV2_FLAG + * - DMAMUX_SYNC_OV3_FLAG + * - DMAMUX_SYNC_OV4_FLAG + * - DMAMUX_SYNC_OV5_FLAG + * - DMAMUX_SYNC_OV6_FLAG + * - DMAMUX_SYNC_OV7_FLAG + * @retval none. + */ +void dmamux_sync_flag_clear(dma_type *dma_x, uint32_t flag) +{ + dma_x->muxsyncclr = flag; +} + +/** + * @brief dmamux request generator flag get. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_GEN_TRIG_OV1_FLAG + * - DMAMUX_GEN_TRIG_OV2_FLAG + * - DMAMUX_GEN_TRIG_OV3_FLAG + * - DMAMUX_GEN_TRIG_OV4_FLAG + * @retval state of dmamux sync flag. + */ +flag_status dmamux_generator_flag_get(dma_type *dma_x, uint32_t flag) +{ + if((dma_x->muxgsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dmamux request generator flag clear. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_GEN_TRIG_OV1_FLAG + * - DMAMUX_GEN_TRIG_OV2_FLAG + * - DMAMUX_GEN_TRIG_OV3_FLAG + * - DMAMUX_GEN_TRIG_OV4_FLAG + * @retval none. + */ +void dmamux_generator_flag_clear(dma_type *dma_x, uint32_t flag) +{ + dma_x->muxgclr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c new file mode 100644 index 0000000000..53bc9b345a --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c @@ -0,0 +1,528 @@ +/** + ************************************************************************** + * @file at32f435_437_dvp.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dvp firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DVP + * @brief DVP driver modules + * @{ + */ + +#ifdef DVP_MODULE_ENABLED + +/** @defgroup DVP_private_functions + * @{ + */ + +/** + * @brief reset the dvp register + * @param none + * @retval none + */ +void dvp_reset(void) +{ + crm_periph_reset(CRM_DVP_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_DVP_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable dvp capture + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_capture_enable(confirm_state new_state) +{ + DVP->ctrl_bit.cap = new_state; +} + +/** + * @brief set dvp capture mode + * @param cap_mode + * this parameter can be one of the following values: + * - DVP_CAP_FUNC_MODE_CONTINUOUS + * - DVP_CAP_FUNC_MODE_SINGLE + * @retval none + */ +void dvp_capture_mode_set(dvp_cfm_type cap_mode) +{ + DVP->ctrl_bit.cfm = cap_mode; +} + +/** + * @brief set dvp cropping window enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_window_crop_enable(confirm_state new_state) +{ + DVP->ctrl_bit.crp = new_state; +} + +/** + * @brief set dvp cropping window configuration + * @param crop_x: cropping window horizontal start pixel + * @param crop_y: cropping window vertical start line + * @param crop_w: cropping window horizontal pixel number + * @param crop_h: cropping window vertical line number + * @param bytes: the number of bytes corresponding to one pixel + * eg. y8:bytes = 1, rgb565:bytes = 2 + * @retval none + */ +void dvp_window_crop_set(uint16_t crop_x, uint16_t crop_y, uint16_t crop_w, uint16_t crop_h, uint8_t bytes) +{ + DVP->cwst = ((crop_x * bytes) | (crop_y << 16)); + DVP->cwsz = ((crop_w * bytes - 1) | ((crop_h - 1) << 16)); +} + +/** + * @brief enable or disable dvp jpeg + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_jpeg_enable(confirm_state new_state) +{ + DVP->ctrl_bit.jpeg = new_state; +} + +/** + * @brief set dvp synchronization mode + * @param sync_mode + * this parameter can be one of the following values: + * - DVP_SYNC_MODE_HARDWARE + * - DVP_SYNC_MODE_EMBEDDED + * @retval none + */ +void dvp_sync_mode_set(dvp_sm_type sync_mode) +{ + DVP->ctrl_bit.sm = sync_mode; +} + +/** + * @brief set dvp synchronization code configuration + * @param fmsc(0x00~0xFF): frame start code + * @param fmec(0x00~0xFF): frame end code + * @param lnsc(0x00~0xFF): line start code + * @param lnec(0x00~0xFF): line end code + * @retval none + */ +void dvp_sync_code_set(uint8_t fmsc, uint8_t fmec, uint8_t lnsc, uint8_t lnec) +{ + DVP->scr = (fmsc | (lnsc << 8) | (lnec << 16) | (fmec << 24)); +} + +/** + * @brief set dvp synchronization unmask configuration + * @param fmsu(0x00~0xFF): frame start unmask + * @param fmeu(0x00~0xFF): frame end unmask + * @param lnsu(0x00~0xFF): line start unmask + * @param lneu(0x00~0xFF): line end unmask + * @retval none + */ +void dvp_sync_unmask_set(uint8_t fmsu, uint8_t fmeu, uint8_t lnsu, uint8_t lneu) +{ + DVP->sur = (fmsu | (lnsu << 8) | (lneu << 16) | (fmeu << 24)); +} + +/** + * @brief set dvp pixel clock polarity + * @param edge + * this parameter can be one of the following values: + * - DVP_CLK_POLARITY_RISING + * - DVP_CLK_POLARITY_FALLING + * @retval none + */ +void dvp_pclk_polarity_set(dvp_ckp_type edge) +{ + DVP->ctrl_bit.ckp = edge; +} + +/** + * @brief set dvp horizontal synchronization polarity + * @param hsync_pol + * this parameter can be one of the following values: + * - DVP_HSYNC_POLARITY_HIGH + * - DVP_HSYNC_POLARITY_LOW + * @retval none + */ +void dvp_hsync_polarity_set(dvp_hsp_type hsync_pol) +{ + DVP->ctrl_bit.hsp = hsync_pol; +} + +/** + * @brief set dvp vertical synchronization polarity + * @param vsync_pol + * this parameter can be one of the following values: + * - DVP_VSYNC_POLARITY_LOW + * - DVP_VSYNC_POLARITY_HIGH + * @retval none + */ +void dvp_vsync_polarity_set(dvp_vsp_type vsync_pol) +{ + DVP->ctrl_bit.vsp = vsync_pol; +} + +/** + * @brief config dvp basic frame rate control + * @note this function only work in continuous fire mode(ctrl_bit.cfm = 0) + * @param dvp_bfrc + * this parameter can be one of the following values: + * - DVP_BFRC_ALL + * - DVP_BFRC_HALF + * - DVP_BFRC_QUARTER + * @retval none + */ +void dvp_basic_frame_rate_control_set(dvp_bfrc_type dvp_bfrc) +{ + DVP->ctrl_bit.bfrc = dvp_bfrc; +} + +/** + * @brief config dvp pixel data length + * @param dvp_pdl + * this parameter can be one of the following values: + * - DVP_PIXEL_DATA_LENGTH_8 + * - DVP_PIXEL_DATA_LENGTH_10 + * - DVP_PIXEL_DATA_LENGTH_12 + * - DVP_PIXEL_DATA_LENGTH_14 + * @retval none + */ +void dvp_pixel_data_length_set(dvp_pdl_type dvp_pdl) +{ + DVP->ctrl_bit.pdl = dvp_pdl; +} + +/** + * @brief enable or disable dvp function + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enable(confirm_state new_state) +{ + DVP->ctrl_bit.ena = new_state; +} + +/** + * @brief set dvp zoomout select + * @param dvp_pcdes: pixel capture/drop selection extension (Only work when pcdc = 2) + * this parameter can be one of the following values: + * - DVP_PCDES_CAP_FIRST + * - DVP_PCDES_DROP_FIRST + * @retval none + */ +void dvp_zoomout_select(dvp_pcdes_type dvp_pcdes) +{ + DVP->actrl_bit.pcdes = dvp_pcdes; +} + +/** + * @brief set dvp zoomout configuration + * @param dvp_pcdc: basic pixel capture/drop control + * this parameter can be one of the following values: + * - DVP_PCDC_ALL + * - DVP_PCDC_ONE_IN_TWO + * - DVP_PCDC_ONE_IN_FOUR + * - DVP_PCDC_TWO_IN_FOUR + * @param dvp_pcds: pixel capture/drop selection + * this parameter can be one of the following values: + * - DVP_PCDS_CAP_FIRST + * - DVP_PCDS_DROP_FIRST + * @param dvp_lcdc: line capture/drop control + * this parameter can be one of the following values: + * - DVP_LCDC_ALL + * - DVP_LCDC_ONE_IN_TWO + * @param dvp_lcds: line capture/drop selection + * this parameter can be one of the following values: + * - DVP_LCDS_CAP_FIRST + * - DVP_LCDS_DROP_FIRST + * @retval none + */ +void dvp_zoomout_set(dvp_pcdc_type dvp_pcdc, dvp_pcds_type dvp_pcds, dvp_lcdc_type dvp_lcdc, dvp_lcds_type dvp_lcds) +{ + DVP->ctrl_bit.pcdc = dvp_pcdc; + DVP->ctrl_bit.pcds = dvp_pcds; + DVP->ctrl_bit.lcdc = dvp_lcdc; + DVP->ctrl_bit.lcds = dvp_lcds; +} + +/** + * @brief get dvp basic status + * @param dvp_status_basic_type: + * this parameter can be one of the following values: + * - DVP_STATUS_HSYN + * - DVP_STATUS_VSYN + * - DVP_STATUS_OFNE + * @retval flag_status (SET or RESET) + */ +flag_status dvp_basic_status_get(dvp_status_basic_type dvp_status_basic) +{ + flag_status status = RESET; + + if ((DVP->sts & (0x1 << dvp_status_basic)) != (uint16_t)RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief enable or disable dvp interrupt + * @param dvp_int: + * this parameter can be any combination of the following values: + * - DVP_CFD_INT + * - DVP_OVR_INT + * - DVP_ESE_INT + * - DVP_VS_INT + * - DVP_HS_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_interrupt_enable(uint32_t dvp_int, confirm_state new_state) +{ + if(new_state == TRUE) + { + DVP->ier |= dvp_int; + } + else + { + DVP->ier &= ~dvp_int; + } +} + +/** + * @brief get dvp event/interrupt flag status + * @param flag + * this parameter can be one of the following values: + * event flag: + * - DVP_CFD_EVT_FLAG + * - DVP_OVR_EVT_FLAG + * - DVP_ESE_EVT_FLAG + * - DVP_VS_EVT_FLAG + * - DVP_HS_EVT_FLAG + * interrupt flag: + * - DVP_CFD_INT_FLAG + * - DVP_OVR_INT_FLAG + * - DVP_ESE_INT_FLAG + * - DVP_VS_INT_FLAG + * - DVP_HS_INT_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status dvp_flag_get(uint32_t flag) +{ + flag_status status = RESET; + if(flag & 0x80000000) + { + if((DVP->ists & flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + } + else + { + if((DVP->ests & flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + } + return status; +} + +/** + * @brief clear dvp's pending flags + * @param flag + * this parameter can be one of the following values: + * event flag: + * - DVP_CFD_EVT_FLAG + * - DVP_OVR_EVT_FLAG + * - DVP_ESE_EVT_FLAG + * - DVP_VS_EVT_FLAG + * - DVP_HS_EVT_FLAG + * interrupt flag: + * - DVP_CFD_INT_FLAG + * - DVP_OVR_INT_FLAG + * - DVP_ESE_INT_FLAG + * - DVP_VS_INT_FLAG + * - DVP_HS_INT_FLAG + * @retval none + */ +void dvp_flag_clear(uint32_t flag) +{ + flag &= ~0x80000000; + DVP->iclr = flag; +} + +/** + * @brief set dvp enhanced image scaling resize enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enhanced_scaling_resize_enable(confirm_state new_state) +{ + DVP->actrl_bit.eisre = new_state; +} +/** + * @brief set dvp enhanced image scaling resize configuration + * @param src_w(0x0001~0x1FFF): horizontal scaling resize source size (source image width) + * @param des_w(0x0001~0x1FFF): horizontal scaling resize target size (target image width) + * @param src_h(0x0001~0x1FFF): vertical scaling resize source size (source image height) + * @param des_h(0x0001~0x1FFF): vertical scaling resize target size (target image height) + * @retval none + */ +void dvp_enhanced_scaling_resize_set(uint16_t src_w, uint16_t des_w, uint16_t src_h, uint16_t des_h) +{ + if((!DVP->ctrl_bit.pcdc) && (!DVP->ctrl_bit.lcdc) && DVP->actrl_bit.efdf) + { + DVP->hscf = (src_w | (des_w << 16)); + DVP->vscf = (src_h | (des_h << 16)); + } +} + +/** + * @brief set enhanced frame rate control configuration + * @param efrcsf(0x00~0x1F): original frame rate contorl factor + * @param efrctf(0x00~0x1F): enhanced frame rate contorl factor + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enhanced_framerate_set(uint16_t efrcsf, uint16_t efrctf, confirm_state new_state) +{ + if((!DVP->ctrl_bit.cfm) && (!DVP->ctrl_bit.bfrc) && (efrctf <= efrcsf)) + { + DVP->frf = (efrcsf | (efrctf << 8)); + } + + DVP->actrl_bit.efrce = new_state; +} + +/** + * @brief set dvp monochrome image binarization configuration + * @param mibthd(0x00~0xFF): monochrome image binarization threshold + * @param new_state: (TRUE or FALSE) + * @retval none + */ +void dvp_monochrome_image_binarization_set(uint8_t mibthd, confirm_state new_state) +{ + DVP->bth_bit.mibthd = mibthd; + DVP->actrl_bit.mibe = new_state; +} + +/** + * @brief set dvp enhanced function data format configuration + * @param dvp_efdf: enhanced function data format + * this parameter can be one of the following values: + * - DVP_EFDF_BYPASS + * - DVP_EFDF_YUV422_UYVY + * - DVP_EFDF_YUV422_YUYV + * - DVP_EFDF_RGB565_555 + * - DVP_EFDF_Y8 + * @retval none + */ +void dvp_enhanced_data_format_set(dvp_efdf_type dvp_efdf) +{ + DVP->actrl_bit.efdf = dvp_efdf; +} + +/** + * @brief set dvp input data un-used condition/number configuration + * @param dvp_idus: input data un-used condition + * this parameter can be one of the following values: + * - DVP_IDUS_MSB + * - DVP_IDUS_LSB + * @param dvp_idun: input data un-used number + * this parameter can be one of the following values: + * - DVP_IDUN_0 + * - DVP_IDUN_2 + * - DVP_IDUN_4 + * - DVP_IDUN_6 + * @retval none + */ +void dvp_input_data_unused_set(dvp_idus_type dvp_idus, dvp_idun_type dvp_idun) +{ + DVP->actrl_bit.idus = dvp_idus; + DVP->actrl_bit.idun = dvp_idun; +} + +/** + * @brief set dvp dma burst transfer configuration + * @param dvp_dmabt: dma burst transfer configuration + * this parameter can be one of the following values: + * - DVP_DMABT_SINGLE + * - DVP_DMABT_BURST + * @retval none + */ +void dvp_dma_burst_set(dvp_dmabt_type dvp_dmabt) +{ + DVP->actrl_bit.dmabt = dvp_dmabt; +} + +/** + * @brief set dvp hsync/vsync event interrupt strategy configuration + * @param dvp_hseid: hsync event interrupt strategy + * this parameter can be one of the following values: + * - DVP_HSEID_LINE_END + * - DVP_HSEID_LINE_START + * @param dvp_vseid: vsync event interrupt strategy + * this parameter can be one of the following values: + * - DVP_VSEID_FRAME_END + * - DVP_VSEID_FRMAE_START + * @retval none + */ +void dvp_sync_event_interrupt_set(dvp_hseid_type dvp_hseid, dvp_vseid_type dvp_vseid) +{ + DVP->actrl_bit.hseid = dvp_hseid; + DVP->actrl_bit.vseid = dvp_vseid; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c new file mode 100644 index 0000000000..88eb5c03e7 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c @@ -0,0 +1,931 @@ +/** + ************************************************************************** + * @file at32f435_437_edma.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the edma firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EDMA + * @brief EDMA driver modules + * @{ + */ + +#ifdef EDMA_MODULE_ENABLED + +/** @defgroup EDMA_private_functions + * @{ + */ + +/** + * @brief reset edma_streamx channely register. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval none. + */ +void edma_reset(edma_stream_type *edma_streamx) +{ + /* reset registers for the selected stream */ + edma_streamx->ctrl_bit.sen = FALSE; + edma_streamx->ctrl = 0x0; + edma_streamx->dtcnt = 0x0; + edma_streamx->paddr = 0x0; + edma_streamx->m0addr = 0x0; + edma_streamx->m1addr = 0x0; + edma_streamx->fctrl = (uint32_t)0x00000021; + + /* reset interrupt pending bits for the selected stream */ + switch((uint32_t)edma_streamx) + { + case EDMA_STREAM1_BASE: + EDMA->clr1 = EDMA_STREAM1_INT_MASK; + break; + case EDMA_STREAM2_BASE: + EDMA->clr1 = EDMA_STREAM2_INT_MASK; + break; + case EDMA_STREAM3_BASE: + EDMA->clr1 = EDMA_STREAM3_INT_MASK; + break; + case EDMA_STREAM4_BASE: + EDMA->clr1 = EDMA_STREAM4_INT_MASK; + break; + case EDMA_STREAM5_BASE: + EDMA->clr2 = EDMA_STREAM5_INT_MASK; + break; + case EDMA_STREAM6_BASE: + EDMA->clr2 = EDMA_STREAM6_INT_MASK; + break; + case EDMA_STREAM7_BASE: + EDMA->clr2 = EDMA_STREAM7_INT_MASK; + break; + case EDMA_STREAM8_BASE: + EDMA->clr2 = EDMA_STREAM8_INT_MASK; + break; + default: break; + } +} + +/** + * @brief edma init. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param edma_init_struct: pointer to a edma_init_type structure. + * @retval none. + */ +void edma_init(edma_stream_type *edma_streamx, edma_init_type *edma_init_struct) +{ + /* config dtd bits */ + edma_streamx->ctrl_bit.dtd = edma_init_struct->direction; + + /* config pincm bit */ + edma_streamx->ctrl_bit.pincm = edma_init_struct->peripheral_inc_enable; + + /* config mincm bit*/ + edma_streamx->ctrl_bit.mincm = edma_init_struct->memory_inc_enable; + + /* config pwidth bits */ + edma_streamx->ctrl_bit.pwidth = edma_init_struct->peripheral_data_width; + + /* config mwidth bits */ + edma_streamx->ctrl_bit.mwidth = edma_init_struct->memory_data_width; + + /* config lm bit */ + edma_streamx->ctrl_bit.lm = edma_init_struct->loop_mode_enable; + + /* config spl bits */ + edma_streamx->ctrl_bit.spl = edma_init_struct->priority; + + /* config mct bits */ + edma_streamx->ctrl_bit.mct = edma_init_struct->memory_burst_mode; + + /* config pct bits */ + edma_streamx->ctrl_bit.pct = edma_init_struct->peripheral_burst_mode; + + /* config fen bits */ + edma_streamx->fctrl_bit.fen = edma_init_struct->fifo_mode_enable; + + /* config fthsel bits*/ + edma_streamx->fctrl_bit.fthsel = edma_init_struct->fifo_threshold; + + /* config dtcnt */ + edma_streamx->dtcnt = edma_init_struct->buffer_size; + + /* config paddr */ + edma_streamx->paddr = edma_init_struct->peripheral_base_addr; + + /* config m0addr */ + edma_streamx->m0addr = edma_init_struct->memory0_base_addr; +} + +/** + * @brief edma init struct config with its default value. + * @param edma_init_struct: pointer to a edma_init_type structure which will be initialized. + * @retval none. + */ +void edma_default_para_init(edma_init_type *edma_init_struct) +{ + edma_init_struct->buffer_size = 0; + edma_init_struct->loop_mode_enable = FALSE; + edma_init_struct->direction = EDMA_DIR_PERIPHERAL_TO_MEMORY; + edma_init_struct->fifo_threshold = EDMA_FIFO_THRESHOLD_1QUARTER; + edma_init_struct->fifo_mode_enable = FALSE; + edma_init_struct->memory0_base_addr = 0; + edma_init_struct->memory_burst_mode = EDMA_MEMORY_SINGLE; + edma_init_struct->memory_data_width = EDMA_MEMORY_DATA_WIDTH_BYTE; + edma_init_struct->memory_inc_enable = FALSE; + edma_init_struct->peripheral_base_addr = 0; + edma_init_struct->peripheral_burst_mode = EDMA_PERIPHERAL_SINGLE; + edma_init_struct->peripheral_data_width = EDMA_PERIPHERAL_DATA_WIDTH_BYTE; + edma_init_struct->peripheral_inc_enable = FALSE; + edma_init_struct->priority = EDMA_PRIORITY_LOW; +} + +/** + * @brief enable or disable the edma streamx. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_stream_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + edma_streamx->ctrl_bit.sen = new_state; +} + +/** + * @brief enable or disable the edma streamx interrupts. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param edma_int: + * this parameter can be one of the following values: + * - EDMA_FDT_INT + * - EDMA_HDT_INT + * - EDMA_DTERR_INT + * - EDMA_DMERR_INT + * - EDMA_FERR_INT + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_interrupt_enable(edma_stream_type *edma_streamx, uint32_t edma_int, confirm_state new_state) +{ + if((edma_int & EDMA_FERR_INT) != 0) + { + if(new_state != FALSE) + { + edma_streamx->fctrl |= (uint32_t)EDMA_FERR_INT; + } + else + { + edma_streamx->fctrl &= ~(uint32_t)EDMA_FERR_INT; + } + } + + if(edma_int != EDMA_FERR_INT) + { + if(new_state != FALSE) + { + edma_streamx->ctrl |= (uint32_t)edma_int; + } + else + { + edma_streamx->ctrl &= ~(uint32_t)edma_int; + } + } +} + +/** + * @brief config the edma peripheral increment offset size mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param offset: peripheral increment offset size. + * this parameter can be one of the following values: + * - EDMA_PERIPHERAL_INC_PSIZE + * - EDMA_PERIPHERAL_INC_4_BYTE + * @retval none. + */ +void edma_peripheral_inc_offset_set(edma_stream_type *edma_streamx, edma_peripheral_inc_offset_type offset) +{ + edma_streamx->ctrl_bit.pincos = offset; +} + +/** + * @brief enable or disable the edma streamx flow controller. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_flow_controller_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + edma_streamx->ctrl_bit.pfctrl = new_state; +} + +/** + * @brief set the number of data to be transferred. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param data_number: the number of data to be transferred (0x0000~0xFFFF). + * @retval none. + */ +void edma_data_number_set(edma_stream_type *edma_streamx, uint16_t data_number) +{ + /* write the number of data units to be transferred */ + edma_streamx->dtcnt = data_number; +} + +/** + * @brief get the number of data to be transferred. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the number value. + */ +uint16_t edma_data_number_get(edma_stream_type *edma_streamx) +{ + return ((uint16_t)(edma_streamx->dtcnt)); +} + +/** + * @brief config the the double buffer mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param memory1_addr: the address of the second buffer. + * @param current_memory: specifies the target area of the first transfer. + * this parameter can be one of the following values: + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + * @retval none. + */ +void edma_double_buffer_mode_init(edma_stream_type *edma_streamx, uint32_t memory1_addr, edma_memory_type current_memory) +{ + if(current_memory != EDMA_MEMORY_0) + { + edma_streamx->ctrl_bit.cm = 1; + } + else + { + edma_streamx->ctrl_bit.cm = 0; + } + + edma_streamx->m1addr = memory1_addr; +} + +/** + * @brief enable or disable the double memory mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_double_buffer_mode_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + if(new_state != FALSE) + { + edma_streamx->ctrl_bit.dmm = 1; + } + else + { + edma_streamx->ctrl_bit.dmm = 0; + } +} + +/** + * @brief config the memory address in double buffer mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param memory_addr: the address of the buffer. + * @param memory_target: indicates the which memory addr register will be config. + * this parameter can be one of the following values: + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + * @retval none. + */ +void edma_memory_addr_set(edma_stream_type *edma_streamx, uint32_t memory_addr, uint32_t memory_target) +{ + if(memory_target != EDMA_MEMORY_0) + { + edma_streamx->m1addr = memory_addr; + } + else + { + edma_streamx->m0addr = memory_addr; + } +} + +/** + * @brief get the current memory target. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the memory target + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + */ +edma_memory_type edma_memory_target_get(edma_stream_type *edma_streamx) +{ + return (edma_memory_type)(edma_streamx->ctrl_bit.cm); +} + +/** + * @brief get the enable status of edma streamx. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval current state of the edma streamx (SET or RESET). + */ +flag_status edma_stream_status_get(edma_stream_type *edma_streamx) +{ + if((edma_streamx->ctrl_bit.sen) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief get the fifo level status. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the fifo filling state. + * - EDMA_FIFO_STATUS_LESS_1QUARTER: (0) < fifo level < (1/4). + * - EDMA_FIFO_STATUS_1QUARTER: (1/4) <= fifo level < (1/2) . + * - EDMA_FIFO_STATUS_HALF: (1/2) <= fifo level < (3/4). + * - EDMA_FIFO_STATUS_3QUARTER: (3/4) <= fifo level < (1). + * - EDMA_FIFO_STATUS_EMPTY: fifo is empty. + * - EDMA_FIFO_STATUS_FULL: fifo is full. + */ +uint8_t edma_fifo_status_get(edma_stream_type *edma_streamx) +{ + return (uint8_t)(edma_streamx->fctrl_bit.fsts); +} + +/** + * @brief get the edma flag. + * @param edma_flag: + * this parameter can be one of the following values: + * - EDMA_FERR1_FLAG - EDMA_DMERR1_FLAG - EDMA_DTERR1_FLAG - EDMA_HDT1_FLAG - EDMA_FDT1_FLAG + * - EDMA_FERR2_FLAG - EDMA_DMERR2_FLAG - EDMA_DTERR2_FLAG - EDMA_HDT2_FLAG - EDMA_FDT2_FLAG + * - EDMA_FERR3_FLAG - EDMA_DMERR3_FLAG - EDMA_DTERR3_FLAG - EDMA_HDT3_FLAG - EDMA_FDT3_FLAG + * - EDMA_FERR4_FLAG - EDMA_DMERR4_FLAG - EDMA_DTERR4_FLAG - EDMA_HDT4_FLAG - EDMA_FDT4_FLAG + * - EDMA_FERR5_FLAG - EDMA_DMERR5_FLAG - EDMA_DTERR5_FLAG - EDMA_HDT5_FLAG - EDMA_FDT5_FLAG + * - EDMA_FERR6_FLAG - EDMA_DMERR6_FLAG - EDMA_DTERR6_FLAG - EDMA_HDT6_FLAG - EDMA_FDT6_FLAG + * - EDMA_FERR7_FLAG - EDMA_DMERR7_FLAG - EDMA_DTERR7_FLAG - EDMA_HDT7_FLAG - EDMA_FDT7_FLAG + * - EDMA_FERR8_FLAG - EDMA_DMERR8_FLAG - EDMA_DTERR8_FLAG - EDMA_HDT8_FLAG - EDMA_FDT8_FLAG + * @retval the new state of edma flag (SET or RESET). + */ +flag_status edma_flag_get(uint32_t edma_flag) +{ + uint32_t status; + + if(edma_flag > ((uint32_t)0x20000000)) + { + status = EDMA->sts2; + } + else + { + status = EDMA->sts1; + } + + if((status & edma_flag) != ((uint32_t)RESET)) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear the edma flag. + * @param edma_flag: + * this parameter can be one of the following values: + * - EDMA_FERR1_FLAG - EDMA_DMERR1_FLAG - EDMA_DTERR1_FLAG - EDMA_HDT1_FLAG - EDMA_FDT1_FLAG + * - EDMA_FERR2_FLAG - EDMA_DMERR2_FLAG - EDMA_DTERR2_FLAG - EDMA_HDT2_FLAG - EDMA_FDT2_FLAG + * - EDMA_FERR3_FLAG - EDMA_DMERR3_FLAG - EDMA_DTERR3_FLAG - EDMA_HDT3_FLAG - EDMA_FDT3_FLAG + * - EDMA_FERR4_FLAG - EDMA_DMERR4_FLAG - EDMA_DTERR4_FLAG - EDMA_HDT4_FLAG - EDMA_FDT4_FLAG + * - EDMA_FERR5_FLAG - EDMA_DMERR5_FLAG - EDMA_DTERR5_FLAG - EDMA_HDT5_FLAG - EDMA_FDT5_FLAG + * - EDMA_FERR6_FLAG - EDMA_DMERR6_FLAG - EDMA_DTERR6_FLAG - EDMA_HDT6_FLAG - EDMA_FDT6_FLAG + * - EDMA_FERR7_FLAG - EDMA_DMERR7_FLAG - EDMA_DTERR7_FLAG - EDMA_HDT7_FLAG - EDMA_FDT7_FLAG + * - EDMA_FERR8_FLAG - EDMA_DMERR8_FLAG - EDMA_DTERR8_FLAG - EDMA_HDT8_FLAG - EDMA_FDT8_FLAG + * @retval none. + */ +void edma_flag_clear(uint32_t edma_flag) +{ + if(edma_flag > ((uint32_t)0x20000000)) + { + EDMA->clr2 = (uint32_t)(edma_flag & 0x0FFFFFFF); + } + else + { + EDMA->clr1 = edma_flag; + } +} + +/** + * @brief initialize the edma 2d mode. + * @param edma_streamx_2d: + * this parameter can be one of the following values: + * - EDMA_STREAM1_2D + * - EDMA_STREAM2_2D + * - EDMA_STREAM3_2D + * - EDMA_STREAM4_2D + * - EDMA_STREAM5_2D + * - EDMA_STREAM6_2D + * - EDMA_STREAM7_2D + * - EDMA_STREAM8_2D + * @param src_stride: source stride(-32768 ~ 32767). + * @param dst_stride: destination stride(-32768 ~ 32767). + * @param xcnt: x dimension transfer count(0x0000~ 0xFFFF). + * @param ycnt: y dimension transfer count(0x0000~ 0xFFFF). + * @retval none. + */ +void edma_2d_init(edma_stream_2d_type *edma_streamx_2d, int16_t src_stride, int16_t dst_stride, uint16_t xcnt, uint16_t ycnt) +{ + edma_streamx_2d->s2dcnt = (uint32_t)((ycnt << 16) | (xcnt)); + + edma_streamx_2d->stride = (uint32_t)((dst_stride << 16) | (src_stride)); +} + +/** + * @brief enable or disable the edma 2d mode. + * @param edma_streamx_2d: + * this parameter can be one of the following values: + * - EDMA_STREAM1_2D + * - EDMA_STREAM2_2D + * - EDMA_STREAM3_2D + * - EDMA_STREAM4_2D + * - EDMA_STREAM5_2D + * - EDMA_STREAM6_2D + * - EDMA_STREAM7_2D + * - EDMA_STREAM8_2D + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_2d_enable(edma_stream_2d_type *edma_streamx_2d, confirm_state new_state) +{ + uint32_t offset; + + offset = ((uint32_t)edma_streamx_2d - EDMA_STREAM1_2D_BASE) / 4; + + if(new_state != FALSE) + { + EDMA->s2dctrl |= (uint16_t)0x0001 << offset; + } + else + { + EDMA->s2dctrl &= ~((uint16_t)0x0001 << offset); + } +} + +/** + * @brief initialize the edma link list. + * @param edma_streamx_ll: + * this parameter can be one of the following values: + * - EDMA_STREAM1_LL + * - EDMA_STREAM2_LL + * - EDMA_STREAM3_LL + * - EDMA_STREAM4_LL + * - EDMA_STREAM5_LL + * - EDMA_STREAM6_LL + * - EDMA_STREAM7_LL + * - EDMA_STREAM8_LL + * @param pointer: link list pointer. + * @retval none. + */ +void edma_link_list_init(edma_stream_link_list_type *edma_streamx_ll, uint32_t pointer) +{ + edma_streamx_ll->llp = pointer; +} + +/** + * @brief enable or disable the edma stream link list mode. + * @param edma_streamx_ll: + * this parameter can be any combination of the following values: + * - EDMA_STREAM1_LL + * - EDMA_STREAM2_LL + * - EDMA_STREAM3_LL + * - EDMA_STREAM4_LL + * - EDMA_STREAM5_LL + * - EDMA_STREAM6_LL + * - EDMA_STREAM7_LL + * - EDMA_STREAM8_LL + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_link_list_enable(edma_stream_link_list_type *edma_streamx_ll, confirm_state new_state) +{ + uint32_t offset; + + offset = ((uint32_t)edma_streamx_ll - EDMA_STREAM1_LL_BASE) / 4; + + if(new_state != FALSE) + { + EDMA->llctrl |= (uint16_t)0x0001 << offset; + } + else + { + EDMA->llctrl &= ~((uint16_t)0x0001 << offset); + } +} + +/** + * @brief enable or disable the edma edmamux. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_enable(confirm_state new_state) +{ + EDMA->muxsel_bit.tblsel = new_state; +} + +/** + * @brief edmamux init. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param edmamux_req_id: + * this parameter can be one of the following values: + * - EDMAMUX_DMAREQ_ID_REQ_G1 - EDMAMUX_DMAREQ_ID_REQ_G2 - EDMAMUX_DMAREQ_ID_REQ_G3 - EDMAMUX_DMAREQ_ID_REQ_G4 + * - EDMAMUX_DMAREQ_ID_ADC1 - EDMAMUX_DMAREQ_ID_ADC2 - EDMAMUX_DMAREQ_ID_ADC3 - EDMAMUX_DMAREQ_ID_DAC1 + * - EDMAMUX_DMAREQ_ID_DAC2 - EDMAMUX_DMAREQ_ID_TMR6_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR7_OVERFLOW- EDMAMUX_DMAREQ_ID_SPI1_RX + * - EDMAMUX_DMAREQ_ID_SPI1_TX - EDMAMUX_DMAREQ_ID_SPI2_RX - EDMAMUX_DMAREQ_ID_SPI2_TX - EDMAMUX_DMAREQ_ID_SPI3_RX + * - EDMAMUX_DMAREQ_ID_SPI3_TX - EDMAMUX_DMAREQ_ID_SPI4_RX - EDMAMUX_DMAREQ_ID_SPI4_TX - EDMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - EDMAMUX_DMAREQ_ID_I2S2_EXT_TX - EDMAMUX_DMAREQ_ID_I2S3_EXT_RX - EDMAMUX_DMAREQ_ID_I2S3_EXT_TX - EDMAMUX_DMAREQ_ID_I2C1_RX + * - EDMAMUX_DMAREQ_ID_I2C1_TX - EDMAMUX_DMAREQ_ID_I2C2_RX - EDMAMUX_DMAREQ_ID_I2C2_TX - EDMAMUX_DMAREQ_ID_I2C3_RX + * - EDMAMUX_DMAREQ_ID_I2C3_TX - EDMAMUX_DMAREQ_ID_USART1_RX - EDMAMUX_DMAREQ_ID_USART1_TX - EDMAMUX_DMAREQ_ID_USART2_RX + * - EDMAMUX_DMAREQ_ID_USART2_TX - EDMAMUX_DMAREQ_ID_USART3_RX - EDMAMUX_DMAREQ_ID_USART3_TX - EDMAMUX_DMAREQ_ID_UART4_RX + * - EDMAMUX_DMAREQ_ID_UART4_TX - EDMAMUX_DMAREQ_ID_UART5_RX - EDMAMUX_DMAREQ_ID_UART5_TX - EDMAMUX_DMAREQ_ID_USART6_RX + * - EDMAMUX_DMAREQ_ID_USART6_TX - EDMAMUX_DMAREQ_ID_UART7_RX - EDMAMUX_DMAREQ_ID_UART7_TX - EDMAMUX_DMAREQ_ID_UART8_RX + * - EDMAMUX_DMAREQ_ID_UART8_TX - EDMAMUX_DMAREQ_ID_SDIO1 - EDMAMUX_DMAREQ_ID_SDIO2 - EDMAMUX_DMAREQ_ID_QSPI1 + * - EDMAMUX_DMAREQ_ID_QSPI2 - EDMAMUX_DMAREQ_ID_TMR1_CH1 - EDMAMUX_DMAREQ_ID_TMR1_CH2 - EDMAMUX_DMAREQ_ID_TMR1_CH3 + * - EDMAMUX_DMAREQ_ID_TMR1_CH4 - EDMAMUX_DMAREQ_ID_TMR1_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR1_TRIG - EDMAMUX_DMAREQ_ID_TMR1_COM + * - EDMAMUX_DMAREQ_ID_TMR8_CH1 - EDMAMUX_DMAREQ_ID_TMR8_CH2 - EDMAMUX_DMAREQ_ID_TMR8_CH3 - EDMAMUX_DMAREQ_ID_TMR8_CH4 + * - EDMAMUX_DMAREQ_ID_TMR8_UP - EDMAMUX_DMAREQ_ID_TMR8_TRIG - EDMAMUX_DMAREQ_ID_TMR8_COM - EDMAMUX_DMAREQ_ID_TMR2_CH1 + * - EDMAMUX_DMAREQ_ID_TMR2_CH2 - EDMAMUX_DMAREQ_ID_TMR2_CH3 - EDMAMUX_DMAREQ_ID_TMR2_CH4 - EDMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR2_TRIG - EDMAMUX_DMAREQ_ID_TMR3_CH1 - EDMAMUX_DMAREQ_ID_TMR3_CH2 - EDMAMUX_DMAREQ_ID_TMR3_CH3 + * - EDMAMUX_DMAREQ_ID_TMR3_CH4 - EDMAMUX_DMAREQ_ID_TMR3_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR3_TRIG - EDMAMUX_DMAREQ_ID_TMR4_CH1 + * - EDMAMUX_DMAREQ_ID_TMR4_CH2 - EDMAMUX_DMAREQ_ID_TMR4_CH3 - EDMAMUX_DMAREQ_ID_TMR4_CH4 - EDMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR4_TRIG - EDMAMUX_DMAREQ_ID_TMR5_CH1 - EDMAMUX_DMAREQ_ID_TMR5_CH2 - EDMAMUX_DMAREQ_ID_TMR5_CH3 + * - EDMAMUX_DMAREQ_ID_TMR5_CH4 - EDMAMUX_DMAREQ_ID_TMR5_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR5_TRIG - EDMAMUX_DMAREQ_ID_TMR20_CH1 + * - EDMAMUX_DMAREQ_ID_TMR20_CH2 - EDMAMUX_DMAREQ_ID_TMR20_CH3 - EDMAMUX_DMAREQ_ID_TMR20_CH4 - EDMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR20_TRIG - EDMAMUX_DMAREQ_ID_TMR20_HALL - EDMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void edmamux_init(edmamux_channel_type *edmamux_channelx, edmamux_requst_id_sel_type edmamux_req_id) +{ + edmamux_channelx->muxctrl_bit.reqsel = edmamux_req_id; +} + +/** + * @brief edmamux sync init struct config with its default value. + * @param edmamux_sync_init_struct: pointer to a edmamux_sync_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_sync_default_para_init(edmamux_sync_init_type *edmamux_sync_init_struct) +{ + edmamux_sync_init_struct->sync_enable = FALSE; + edmamux_sync_init_struct->sync_event_enable = FALSE; + edmamux_sync_init_struct->sync_polarity = EDMAMUX_SYNC_POLARITY_DISABLE; + edmamux_sync_init_struct->sync_request_number = 0x0; + edmamux_sync_init_struct->sync_signal_sel = EDMAMUX_SYNC_ID_EXINT0; +} + +/** + * @brief edmamux synchronization config. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param edmamux_sync_init_struct: ointer to a edmamux_sync_init_type structure. + * @retval none. + */ +void edmamux_sync_config(edmamux_channel_type *edmamux_channelx, edmamux_sync_init_type *edmamux_sync_init_struct) +{ + edmamux_channelx->muxctrl_bit.syncsel = edmamux_sync_init_struct->sync_signal_sel; + edmamux_channelx->muxctrl_bit.syncpol = edmamux_sync_init_struct->sync_polarity; + edmamux_channelx->muxctrl_bit.reqcnt = edmamux_sync_init_struct->sync_request_number; + edmamux_channelx->muxctrl_bit.evtgen = edmamux_sync_init_struct->sync_event_enable; + edmamux_channelx->muxctrl_bit.syncen = edmamux_sync_init_struct->sync_enable; +} + +/** + * @brief edmamux request generator init struct config with its default value. + * @param edmamux_gen_init_struct: pointer to a edmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_generator_default_para_init(edmamux_gen_init_type *edmamux_gen_init_struct) +{ + edmamux_gen_init_struct->gen_enable = FALSE; + edmamux_gen_init_struct->gen_polarity = EDMAMUX_GEN_POLARITY_DISABLE; + edmamux_gen_init_struct->gen_request_number = 0x0; + edmamux_gen_init_struct->gen_signal_sel = EDMAMUX_GEN_ID_EXINT0; +} + +/** + * @brief edmamux request generator init. + * @param edmamux_gen_init_struct: pointer to a edmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_generator_config(edmamux_generator_type *edmamux_gen_x, edmamux_gen_init_type *edmamux_gen_init_struct) +{ + edmamux_gen_x->gctrl_bit.sigsel = edmamux_gen_init_struct->gen_signal_sel; + edmamux_gen_x->gctrl_bit.gpol = edmamux_gen_init_struct->gen_polarity; + edmamux_gen_x->gctrl_bit.greqcnt = edmamux_gen_init_struct->gen_request_number; + edmamux_gen_x->gctrl_bit.gen = edmamux_gen_init_struct->gen_enable; +} + +/** + * @brief enable or disable the edmamux sync interrupts. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_sync_interrupt_enable(edmamux_channel_type *edmamux_channelx, confirm_state new_state) +{ + if(new_state != FALSE) + { + edmamux_channelx->muxctrl_bit.syncovien = TRUE; + } + else + { + edmamux_channelx->muxctrl_bit.syncovien = FALSE; + } +} + +/** + * @brief enable or disable the edmamux request generator interrupts. + * @param edmamux_gen_x: pointer to a edmamux_generator_type structure. + * this parameter can be one of the following values: + * - EDMAMUX_GENERATOR1 + * - EDMAMUX_GENERATOR2 + * - EDMAMUX_GENERATOR3 + * - EDMAMUX_GENERATOR4 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_generator_interrupt_enable(edmamux_generator_type *edmamux_gen_x, confirm_state new_state) +{ + if(new_state != FALSE) + { + edmamux_gen_x->gctrl_bit.trgovien = TRUE; + } + else + { + edmamux_gen_x->gctrl_bit.trgovien = FALSE; + } +} + +/** + * @brief edmamux sync flag get. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_SYNC_OV1_FLAG + * - EDMAMUX_SYNC_OV2_FLAG + * - EDMAMUX_SYNC_OV3_FLAG + * - EDMAMUX_SYNC_OV4_FLAG + * - EDMAMUX_SYNC_OV5_FLAG + * - EDMAMUX_SYNC_OV6_FLAG + * - EDMAMUX_SYNC_OV7_FLAG + * - EDMAMUX_SYNC_OV8_FLAG + * @retval state of edmamux sync flag. + */ +flag_status edmamux_sync_flag_get(uint32_t flag) +{ + if((EDMA->muxsyncsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief edmamux sync flag clear. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_SYNC_OV1_FLAG + * - EDMAMUX_SYNC_OV2_FLAG + * - EDMAMUX_SYNC_OV3_FLAG + * - EDMAMUX_SYNC_OV4_FLAG + * - EDMAMUX_SYNC_OV5_FLAG + * - EDMAMUX_SYNC_OV6_FLAG + * - EDMAMUX_SYNC_OV7_FLAG + * - EDMAMUX_SYNC_OV8_FLAG + * @retval none. + */ +void edmamux_sync_flag_clear(uint32_t flag) +{ + EDMA->muxsyncclr = flag; +} + +/** + * @brief edmamux request generator flag get. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_GEN_TRIG_OV1_FLAG + * - EDMAMUX_GEN_TRIG_OV2_FLAG + * - EDMAMUX_GEN_TRIG_OV3_FLAG + * - EDMAMUX_GEN_TRIG_OV4_FLAG + * @retval state of edmamux sync flag. + */ +flag_status edmamux_generator_flag_get(uint32_t flag) +{ + if((EDMA->muxgsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief edmamux request generator flag clear. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_GEN_TRIG_OV1_FLAG + * - EDMAMUX_GEN_TRIG_OV2_FLAG + * - EDMAMUX_GEN_TRIG_OV3_FLAG + * - EDMAMUX_GEN_TRIG_OV4_FLAG + * @retval none. + */ +void edmamux_generator_flag_clear(uint32_t flag) +{ + EDMA->muxgclr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c new file mode 100644 index 0000000000..c1dbe1ef5e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c @@ -0,0 +1,2309 @@ +/** + ************************************************************************** + * @file at32f435_437_emac.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the emac firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EMAC + * @brief EMAC driver modules + * @{ + */ + +#ifdef EMAC_MODULE_ENABLED + +/** @defgroup EMAC_private_functions + * @{ + */ + +#if defined (EMAC_BASE) +/** + * @brief global pointers on tx and rx descriptor used to track transmit and receive descriptors + */ +emac_dma_desc_type *dma_tx_desc_to_set; +emac_dma_desc_type *dma_rx_desc_to_get; + +/* emac private function */ +static void emac_delay(uint32_t delay); + +/** + * @brief deinitialize the emac peripheral registers to their default reset values. + * @param none + * @retval none + */ +void emac_reset(void) +{ + crm_periph_reset(CRM_EMAC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_EMAC_PERIPH_RESET, FALSE); +} + +/** + * @brief initialize emac control structure + * @param emac_control_config_type + * @retval none + */ +void emac_control_para_init(emac_control_config_type *control_para) +{ + control_para->auto_nego = EMAC_AUTO_NEGOTIATION_OFF; + control_para->auto_pad_crc_strip = FALSE; + control_para->back_off_limit = EMAC_BACKOFF_LIMIT_0; + control_para->carrier_sense_disable = FALSE; + control_para->deferral_check = FALSE; + control_para->duplex_mode = EMAC_HALF_DUPLEX; + control_para->fast_ethernet_speed = EMAC_SPEED_10MBPS; + control_para->interframe_gap = EMAC_INTERFRAME_GAP_96BIT; + control_para->ipv4_checksum_offload = FALSE; + control_para->jabber_disable = FALSE; + control_para->loopback_mode = FALSE; + control_para->receive_own_disable = FALSE; + control_para->retry_disable = FALSE; + control_para->watchdog_disable = FALSE; +} + +/** + * @brief according to hclk to set mdc clock frequency. + * @param none + * @retval none + */ +void emac_clock_range_set(void) +{ + uint8_t bits_value = 0; + crm_clocks_freq_type clocks_freq = {0}; + + /* clear clock range bits */ + EMAC->miiaddr_bit.cr = bits_value; + + crm_clocks_freq_get(&clocks_freq); + + if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_20MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_35MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_20_TO_35; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_35MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_60MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_35_TO_60; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_60MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_100MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_60_TO_100; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_100MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_150MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_100_TO_150; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_150MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_250MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_150_TO_250; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_250MHZ) && (clocks_freq.ahb_freq <= EMAC_HCLK_BORDER_288MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_250_TO_288; + } + + EMAC->miiaddr_bit.cr = bits_value; +} + +/** + * @brief configure emac control setting. + * @param control_struct: control setting of mac control register. + * @retval none + */ +void emac_control_config(emac_control_config_type *control_struct) +{ + emac_deferral_check_set(control_struct->deferral_check); + emac_backoff_limit_set(control_struct->back_off_limit); + emac_auto_pad_crc_stripping_set(control_struct->auto_pad_crc_strip); + emac_retry_disable(control_struct->retry_disable); + emac_ipv4_checksum_offload_set(control_struct->ipv4_checksum_offload); + emac_loopback_mode_enable(control_struct->loopback_mode); + emac_receive_own_disable(control_struct->receive_own_disable); + emac_carrier_sense_disable(control_struct->carrier_sense_disable); + emac_interframe_gap_set(control_struct->interframe_gap); + emac_jabber_disable(control_struct->jabber_disable); + emac_watchdog_disable(control_struct->watchdog_disable); +} + +/** + * @brief reset emac dma + * @param none + * @retval none + */ +void emac_dma_software_reset_set(void) +{ + EMAC_DMA->bm_bit.swr = 1; +} + +/** + * @brief get emac dma reset status + * @param none + * @retval TRUE of FALSE + */ +flag_status emac_dma_software_reset_get(void) +{ + if(EMAC_DMA->bm_bit.swr) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable emac and dma reception/transmission + * @param none + * @retval none + */ +void emac_start(void) +{ + /* enable transmit state machine of the mac for transmission on the mii */ + emac_trasmitter_enable(TRUE); + + /* flush transmit fifo */ + emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE); + + /* enable receive state machine of the mac for reception from the mii */ + emac_receiver_enable(TRUE); + + /* start dma transmission */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, TRUE); + + /* start dma reception */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, TRUE); +} + +/** + * @brief stop emac and dma reception/transmission + * @param none + * @retval none + */ +void emac_stop(void) +{ + /* stop dma transmission */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, FALSE); + + /* stop dma reception */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, FALSE); + + /* stop receive state machine of the mac for reception from the mii */ + emac_receiver_enable(FALSE); + + /* flush transmit fifo */ + emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE); + + /* stop transmit state machine of the mac for transmission on the mii */ + emac_trasmitter_enable(FALSE); +} + + +/** + * @brief write phy data. + * @param address: phy address. + * @param reg: register of phy. + * @param data: value that wants to write to phy. + * @retval SUCCESS or ERROR + */ +error_status emac_phy_register_write(uint8_t address, uint8_t reg, uint16_t data) +{ + uint32_t timeout = 0; + + EMAC->miidt_bit.md = data; + + EMAC->miiaddr_bit.pa = address; + EMAC->miiaddr_bit.mii = reg; + EMAC->miiaddr_bit.mw = 1; + EMAC->miiaddr_bit.mb = 1; + + do + { + timeout++; + } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT)); + + if(timeout == PHY_TIMEOUT) + { + return ERROR; + } + return SUCCESS; +} + +/** + * @brief read phy data + * @param address: phy address. + * @param reg: register of phy. + * @param data: value that is read from phy. + * @retval SUCCESS or ERROR + */ +error_status emac_phy_register_read(uint8_t address, uint8_t reg, uint16_t *data) +{ + uint32_t timeout = 0; + + EMAC->miiaddr_bit.pa = address; + EMAC->miiaddr_bit.mii = reg; + EMAC->miiaddr_bit.mw = 0; + EMAC->miiaddr_bit.mb = 1; + + do + { + timeout++; + *data = EMAC->miidt_bit.md; + } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT)); + + if(timeout == PHY_TIMEOUT) + { + return ERROR; + } + + *data = EMAC->miidt_bit.md; + return SUCCESS; +} + +/** + * @brief emac receiver enable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receiver_enable(confirm_state new_state) +{ + __IO uint32_t temp = 0; + + EMAC->ctrl_bit.re = new_state; + + temp = EMAC->ctrl; + emac_delay(1); + EMAC->ctrl = temp; +} + +/** + * @brief emac transmitter enable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_trasmitter_enable(confirm_state new_state) +{ + __IO uint32_t temp = 0; + + EMAC->ctrl_bit.te = new_state; + + temp = EMAC->ctrl; + emac_delay(1); + EMAC->ctrl = temp; +} + +/** + * @brief emac defferal check enable, only avalible in half-duplex mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_deferral_check_set(confirm_state new_state) +{ + EMAC->ctrl_bit.dc = new_state; +} + +/** + * @brief emac back-off limit, only avalible in half-duplex mode. + * @param slot_time: waiting time of retransmission after collision + * this parameter can be one of the following values: + * - EMAC_BACKOFF_LIMIT_0 + * - EMAC_BACKOFF_LIMIT_1 + * - EMAC_BACKOFF_LIMIT_2 + * - EMAC_BACKOFF_LIMIT_3 + * @retval none + */ +void emac_backoff_limit_set(emac_bol_type slot_time) +{ + EMAC->ctrl_bit.bl = slot_time; +} + +/** + * @brief set mac automatic pad/CRC stripping. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_auto_pad_crc_stripping_set(confirm_state new_state) +{ + EMAC->ctrl_bit.acs = new_state; +} + +/** + * @brief transmittion retry disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_retry_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dr = new_state; +} + +/** + * @brief set ipv4 checksum offload. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ipv4_checksum_offload_set(confirm_state new_state) +{ + EMAC->ctrl_bit.ipc = new_state; +} + +/** + * @brief enable loopback mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_loopback_mode_enable(confirm_state new_state) +{ + EMAC->ctrl_bit.lm = new_state; +} + +/** + * @brief receive own disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_own_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dro = new_state; +} + +/** + * @brief carrier sense disbale. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_carrier_sense_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dcs = new_state; +} + +/** + * @brief set minimum interframe gap between frames during transmission. + * @param number: interframe gap number. + * this parameter can be one of the following values: + * - EMAC_FRAME_GAP_96BIT + * - EMAC_FRAME_GAP_88BIT + * - EMAC_FRAME_GAP_80BIT + * - EMAC_FRAME_GAP_72BIT + * - EMAC_FRAME_GAP_64BIT + * - EMAC_FRAME_GAP_56BIT + * - EMAC_FRAME_GAP_48BIT + * - EMAC_FRAME_GAP_40BIT + * @retval none + */ +void emac_interframe_gap_set(emac_intergrame_gap_type number) +{ + EMAC->ctrl_bit.ifg = number; +} + +/** + * @brief jabber disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_jabber_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.jd = new_state; +} + +/** + * @brief watchdog disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_watchdog_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.wd = new_state; +} + +/** + * @brief set mac fast emac speed. + * @param speed: mac bandwidth + * this parameter can be one of the following values: + * - EMAC_SPEED_10MBPS + * - EMAC_SPEED_100MBPS + * @retval none + */ +void emac_fast_speed_set(emac_speed_type speed) +{ + EMAC->ctrl_bit.fes = speed; +} + +/** + * @brief set duplex mode. + * @param duplex_mode: communication mode + * this parameter can be one of the following values: + * - EMAC_HALF_DUPLEX + * - EMAC_FULL_DUPLEX + * @retval none + */ +void emac_duplex_mode_set(emac_duplex_type duplex_mode) +{ + EMAC->ctrl_bit.dm = duplex_mode; +} + +/** + * @brief set mac promiscuous mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_promiscuous_mode_set(confirm_state new_state) +{ + EMAC->frmf_bit.pr = new_state; +} + +/** + * @brief hash unicast. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_unicast_set(confirm_state new_state) +{ + EMAC->frmf_bit.huc = new_state; +} + +/** + * @brief hash multicast. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_multicast_set(confirm_state new_state) +{ + EMAC->frmf_bit.hmc = new_state; +} + +/** + * @brief destination address inverse filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_dstaddr_inverse_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.daif = new_state; +} + +/** + * @brief pass all multicasting frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_pass_all_multicasting_set(confirm_state new_state) +{ + EMAC->frmf_bit.pmc = new_state; +} + +/** + * @brief broadcast frames disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_broadcast_frames_disable(confirm_state new_state) +{ + EMAC->frmf_bit.dbf = new_state; +} + +/** + * @brief set mac how to pass control frames. + * @param condition: set what control frame can pass filter. + * this parameter can be one of the following values: + * - EMAC_CONTROL_FRAME_PASSING_NO + * - EMAC_CONTROL_FRAME_PASSING_ALL + * - EMAC_CONTROL_FRAME_PASSING_MATCH + * @retval none + */ +void emac_pass_control_frames_set(emac_control_frames_filter_type condition) +{ + EMAC->frmf_bit.pcf = condition; +} + +/** + * @brief source address inverse filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_srcaddr_inverse_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.saif = new_state; +} + +/** + * @brief source address filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_srcaddr_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.saf = new_state; +} + +/** + * @brief mac uses hash or perfect filter. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_perfect_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.hpf = new_state; +} + +/** + * @brief mac receives all frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_all_set(confirm_state new_state) +{ + EMAC->frmf_bit.ra = new_state; +} + +/** + * @brief hash table high 32-bit. + * @param high32bits: the highest 32-bit of hash table. + * @retval none + */ +void emac_hash_table_high32bits_set(uint32_t high32bits) +{ + EMAC->hth_bit.hth = high32bits; +} + +/** + * @brief hash table low 32-bit. + * @param low32bits: the lowest 32-bit of hash table. + * @retval none + */ +void emac_hash_table_low32bits_set(uint32_t low32bits) +{ + EMAC->htl_bit.htl = low32bits; +} + +/** + * @brief mii busy status. + * @param none + * @retval SET or RESET + */ +flag_status emac_mii_busy_get(void) +{ + if(EMAC->miiaddr_bit.mb) { + return SET; + } + else { + return RESET; + } +} + +/** + * @brief tell phy that will be written. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mii_write(confirm_state new_state) +{ + EMAC->miiaddr_bit.mw = new_state; +} + +/** + * @brief set flow control busy in full-duplex mode, back pressure activate in half-duplex mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_fcb_bpa_set(confirm_state new_state) +{ + EMAC->fctrl_bit.fcbbpa = new_state; +} + +/** + * @brief set transmit flow control. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_transmit_flow_control_enable(confirm_state new_state) +{ + EMAC->fctrl_bit.etf = new_state; +} + +/** + * @brief set receive flow control. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_flow_control_enable(confirm_state new_state) +{ + EMAC->fctrl_bit.erf = new_state; +} + +/** + * @brief set unicast pause frame detect. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_unicast_pause_frame_detect(confirm_state new_state) +{ + EMAC->fctrl_bit.dup = new_state; +} + +/** + * @brief set pause low threshold. + * @param pasue_threshold: pause slot time. + * this parameter can be one of the following values: + * - EMAC_PAUSE_4_SLOT_TIME + * - EMAC_PAUSE_28_SLOT_TIME + * - EMAC_PAUSE_144_SLOT_TIME + * - EMAC_PAUSE_256_SLOT_TIME + * @retval none + */ +void emac_pause_low_threshold_set(emac_pause_slot_threshold_type pasue_threshold) +{ + EMAC->fctrl_bit.plt = pasue_threshold; +} + +/** + * @brief set zero-quanta pause disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_zero_quanta_pause_disable(confirm_state new_state) +{ + EMAC->fctrl_bit.dzqp = new_state; +} + +/** + * @brief set pause time. + * @param pause_time: time slots to pause transmit frame. + * @retval none + */ +void emac_pause_time_set(uint16_t pause_time) +{ + EMAC->fctrl_bit.pt = pause_time; +} + +/** + * @brief identify coming vlan frame field with setting value. + * @param identifier: it will be compared with coming frame. + * @retval none + */ +void emac_vlan_tag_identifier_set(uint16_t identifier) +{ + EMAC->vlt_bit.vti = identifier; +} + +/** + * @brief set 12-bit vlan identifier. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_vlan_tag_comparison_set(confirm_state new_state) +{ + EMAC->vlt_bit.etv = new_state; +} + +/** + * @brief set wakeup frame. + * @param value: it will be written to eight non transparent registers. + * @retval none + */ +void emac_wakeup_frame_set(uint32_t value) +{ + EMAC->rwff = value; +} + +/** + * @brief get wakeup frame. + * @param none + * @retval get value from eight non transparent registers. + */ +uint32_t emac_wakeup_frame_get(void) +{ + return (EMAC->rwff); +} + +/** + * @brief all frame will be droppped except wakeup frame or magic packet. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_power_down_set(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.pd = new_state; +} + +/** + * @brief magic packet enable + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_magic_packet_enable(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.emp = new_state; +} + +/** + * @brief wakeup frame enable + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_wakeup_frame_enable(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.erwf = new_state; +} + +/** + * @brief received magic packet + * @param none + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_received_magic_packet_get(void) +{ + if(EMAC->pmtctrlsts_bit.rmp) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief received wakeup frame. + * @param none + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_received_wakeup_frame_get(void) +{ + if(EMAC->pmtctrlsts_bit.rrwf) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief set unicast frame that passes DAF as wakeup frame. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_global_unicast_set(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.guc = new_state; +} + +/** + * @brief reset wakeup frame filter resgister + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_wakeup_frame_filter_reset(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.rwffpr = new_state; +} + +/** + * @brief read interrupt status + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - EMAC_PMT_FLAG + * - EMAC_MMC_FLAG + * - EMAC_MMCR_FLAG + * - EMAC_MMCT_FLAG + * - EMAC_TST_FLAG + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_interrupt_status_read(uint32_t flag) +{ + if(EMAC->ists & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief set interrupt mask + * @param mask_type: mask the interrupt signal + * this parameter can be one of the following values: + * - EMAC_INTERRUPT_PMT_MASK + * - EMAC_INTERRUPT_TST_MASK + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_interrupt_mask_set(emac_interrupt_mask_type mask_type, confirm_state new_state) +{ + switch(mask_type) + { + case EMAC_INTERRUPT_PMT_MASK: + { + EMAC->imr_bit.pim = new_state; + break; + } + case EMAC_INTERRUPT_TST_MASK: + { + EMAC->imr_bit.tim = new_state; + break; + } + } +} + +/** + * @brief set local mac address + * @param address: local address for mac0 + * @retval none + */ +void emac_local_address_set(uint8_t *address) +{ + EMAC->a0h_bit.ma0h = (uint32_t)(address[5] << 8 | address[4]); + EMAC->a0l_bit.ma0l = (uint32_t)(address[3] << 24 | address[2] << 16 | address[1] << 8 | address[0]); +} + +/** + * @brief set mac filter address + * @param mac: select which mac you want to set + * this parameter can be one of the following values: + * - EMAC_ADDRESS_FILTER_1 + * - EMAC_ADDRESS_FILTER_2 + * - EMAC_ADDRESS_FILTER_3 + * @retval none + */ +void emac_address_filter_set(emac_address_type mac, emac_address_filter_type filter, emac_address_mask_type mask_bit, confirm_state new_state) +{ + switch(mac) + { + case EMAC_ADDRESS_FILTER_1: + { + EMAC->a1h_bit.sa = filter; + EMAC->a1h_bit.mbc = mask_bit; + EMAC->a1h_bit.ae = new_state; + break; + } + case EMAC_ADDRESS_FILTER_2: + { + EMAC->a2h_bit.sa = filter; + EMAC->a2h_bit.mbc = mask_bit; + EMAC->a2h_bit.ae = new_state; + break; + } + case EMAC_ADDRESS_FILTER_3: + { + EMAC->a3h_bit.sa = filter; + EMAC->a3h_bit.mbc = mask_bit; + EMAC->a3h_bit.ae = new_state; + break; + } + } +} + +/** + * @brief set transmit/receive descriptor list address + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @param dma_desc_tab: pointer on the first tx desc list + * @param buff: pointer on the first tx/rx buffer list + * @param buffer_count: number of the used Tx desc in the list + * @retval none + */ +void emac_dma_descriptor_list_address_set(emac_dma_tx_rx_type transfer_type, emac_dma_desc_type *dma_desc_tab, uint8_t *buff, uint32_t buffer_count) +{ + uint32_t i = 0; + emac_dma_desc_type *dma_descriptor; + + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + dma_tx_desc_to_set = dma_desc_tab; + for(i = 0; i < buffer_count; i++) + { + dma_descriptor = dma_desc_tab + i; + + dma_descriptor->status = EMAC_DMATXDESC_TCH; + + dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]); + + if(i < (buffer_count - 1)) + { + dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1); + } + else + { + dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab; + } + } + EMAC_DMA->tdladdr_bit.stl = (uint32_t) dma_desc_tab; + break; + } + case EMAC_DMA_RECEIVE: + { + dma_rx_desc_to_get = dma_desc_tab; + for(i = 0; i < buffer_count; i++) + { + dma_descriptor = dma_desc_tab + i; + + dma_descriptor->status = EMAC_DMARXDESC_OWN; + + dma_descriptor->controlsize = EMAC_DMARXDESC_RCH | (uint32_t)EMAC_MAX_PACKET_LENGTH; + + dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]); + + if(i < (buffer_count - 1)) + { + dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1); + } + else + { + dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab; + } + } + EMAC_DMA->rdladdr_bit.srl = (uint32_t) dma_desc_tab; + break; + } + } +} + +/** + * @brief enable or disable the specified dma rx descriptor receive interrupt + * @param dma_rx_desc: pointer on a rx desc. + * @param new_state: new state of the specified dma rx descriptor interrupt. + * this parameter can be one of the following values: + * - TRUE + * - FALSE. + * @retval none + */ +void emac_dma_rx_desc_interrupt_config(emac_dma_desc_type *dma_rx_desc, confirm_state new_state) +{ + if (new_state != FALSE) + { + /* enable the dma rx desc receive interrupt */ + dma_rx_desc->controlsize &= (~(uint32_t)EMAC_DMARXDESC_DIC); + } + else + { + /* disable the dma rx desc receive interrupt */ + dma_rx_desc->controlsize |= EMAC_DMARXDESC_DIC; + } +} + +/** + * @brief get transmit/receive descriptor list address + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @retval transmit/receive descriptor list address + */ +uint32_t emac_dma_descriptor_list_address_get(emac_dma_tx_rx_type transfer_type) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + return (EMAC_DMA->tdladdr_bit.stl); + } + case EMAC_DMA_RECEIVE: + { + return (EMAC_DMA->rdladdr_bit.srl); + } + } + return 0; +} + +/** + * @brief get the size of received the received packet. + * @param none + * @retval received packet size + */ +uint32_t emac_received_packet_size_get(void) +{ + uint32_t frame_length = 0; + if(((dma_rx_desc_to_get->status & EMAC_DMARXDESC_OWN) == (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMATXDESC_ES) == (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_LS) != (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_FS) != (uint32_t)RESET)) + { + frame_length = emac_dmarxdesc_frame_length_get(dma_rx_desc_to_get); + } + + return frame_length; +} + +/** + * @brief get the specified dma rx descsriptor frame length. + * @param dma_rx_desc: pointer on a dma rx descriptor + * @retval the rx descriptor received frame length. + */ +uint32_t emac_dmarxdesc_frame_length_get(emac_dma_desc_type *dma_rx_desc) +{ + return ((dma_rx_desc->status & EMAC_DMARXDESC_FL) >> EMAC_DMARXDESC_FRAME_LENGTHSHIFT); +} + +/** + * @brief init emac dma parameters + * @param emac_dma_config_type + * @retval none + */ +void emac_dma_para_init(emac_dma_config_type *control_para) +{ + control_para->aab_enable = FALSE; + control_para->da_enable = FALSE; + control_para->desc_skip_length = 0; + control_para->dt_disable = FALSE; + control_para->fb_enable = FALSE; + control_para->fef_enable = FALSE; + control_para->flush_rx_disable = FALSE; + control_para->fugf_enable = FALSE; + control_para->osf_enable = FALSE; + control_para->priority_ratio = EMAC_DMA_1_RX_1_TX; + control_para->rsf_enable = FALSE; + control_para->rx_dma_pal = EMAC_DMA_PBL_1; + control_para->rx_threshold = EMAC_DMA_RX_THRESHOLD_64_BYTES; + control_para->tsf_enable = FALSE; + control_para->tx_dma_pal = EMAC_DMA_PBL_1; + control_para->tx_threshold = EMAC_DMA_TX_THRESHOLD_64_BYTES; + control_para->usp_enable = FALSE; +} + +/** + * @brief configure emac dma + * @param emac_dma_config_type + * @retval none + */ +void emac_dma_config(emac_dma_config_type *control_para) +{ + EMAC_DMA->bm_bit.aab = control_para->aab_enable; + EMAC_DMA->bm_bit.dsl = control_para->desc_skip_length; + EMAC_DMA->bm_bit.rdp = control_para->rx_dma_pal; + EMAC_DMA->bm_bit.pbl = control_para->tx_dma_pal; + EMAC_DMA->bm_bit.fb = control_para->fb_enable; + EMAC_DMA->bm_bit.usp = control_para->usp_enable; + EMAC_DMA->bm_bit.da = control_para->da_enable; + EMAC_DMA->bm_bit.pr = control_para->priority_ratio; + + EMAC_DMA->opm_bit.dt = control_para->dt_disable; + EMAC_DMA->opm_bit.rsf = control_para->rsf_enable; + EMAC_DMA->opm_bit.dfrf = control_para->flush_rx_disable; + EMAC_DMA->opm_bit.tsf = control_para->tsf_enable; + EMAC_DMA->opm_bit.ttc = control_para->tx_threshold; + EMAC_DMA->opm_bit.fef = control_para->fef_enable; + EMAC_DMA->opm_bit.fugf = control_para->fugf_enable; + EMAC_DMA->opm_bit.rtc = control_para->rx_threshold; + EMAC_DMA->opm_bit.osf = control_para->osf_enable; +} + +/** + * @brief set rx tx priority + * @param ratio: rx tx priority ratio + * this parameter can be one of the following values: + * - EMAC_DMA_1_RX_1_TX + * - EMAC_DMA_2_RX_1_TX + * - EMAC_DMA_3_RX_1_TX + * - EMAC_DMA_4_RX_1_TX + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_arbitation_set(emac_dma_rx_tx_ratio_type ratio, confirm_state new_state) +{ + EMAC_DMA->bm_bit.da = new_state; + + if(new_state) + { + EMAC_DMA->bm_bit.pr = ratio; + } +} + +/** + * @brief set descriptor skip mength + * @param length: descriptor skip length + * @retval none + */ +void emac_dma_descriptor_skip_length_set(uint8_t length) +{ + EMAC_DMA->bm_bit.dsl = length; +} + +/** + * @brief set programmable burst length + * @param tx_length: tx programmable burst length + * this parameter can be one of the following values: + * - EMAC_DMA_PBL_1 + * - EMAC_DMA_PBL_2 + * - EMAC_DMA_PBL_4 + * - EMAC_DMA_PBL_8 + * - EMAC_DMA_PBL_16 + * - EMAC_DMA_PBL_32 + * @param rx_length: rx programmable burst length + * this parameter can be one of the following values: + * - EMAC_DMA_PBL_1 + * - EMAC_DMA_PBL_2 + * - EMAC_DMA_PBL_4 + * - EMAC_DMA_PBL_8 + * - EMAC_DMA_PBL_16 + * - EMAC_DMA_PBL_32 + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_separate_pbl_set(emac_dma_pbl_type tx_length, emac_dma_pbl_type rx_length, confirm_state new_state) +{ + EMAC_DMA->bm_bit.usp = new_state; + EMAC_DMA->bm_bit.pbl = tx_length; + + if(new_state) + { + EMAC_DMA->bm_bit.pbl = rx_length; + } +} + +/** + * @brief set 8 times programmable burst length + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_eight_pbl_mode_set(confirm_state new_state) +{ + EMAC_DMA->bm_bit.pblx8 = new_state; +} + +/** + * @brief set address-aligned beats + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_address_aligned_beats_set(confirm_state new_state) +{ + EMAC_DMA->bm_bit.aab = new_state; +} + +/** + * @brief set transmit/receive poll demand + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @param value: it can be any number + * @retval none + */ +void emac_dma_poll_demand_set(emac_dma_tx_rx_type transfer_type, uint32_t value) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + EMAC_DMA->tpd_bit.tpd = value; + break; + } + case EMAC_DMA_RECEIVE: + { + EMAC_DMA->rpd_bit.rpd = value; + break; + } + } +} + +/** + * @brief get transmit poll demand + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @retval current transmit descriptor + */ +uint32_t emac_dma_poll_demand_get(emac_dma_tx_rx_type transfer_type) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + return (EMAC_DMA->tpd_bit.tpd); + } + case EMAC_DMA_RECEIVE: + { + return (EMAC_DMA->rpd_bit.rpd); + } + } + return 0; +} + +/** + * @brief get receive dma process status + * @param none + * @retval every situation it describe in RM + * this parameter can be one of the following values: + * - EMAC_DMA_RX_RESET_STOP_COMMAND + * - EMAC_DMA_RX_FETCH_DESCRIPTOR + * - EMAC_DMA_RX_WAITING_PACKET + * - EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE + * - EMAC_DMA_RX_CLOSE_DESCRIPTOR + * - EMAC_DMA_RX_FIFO_TO_HOST + */ +emac_dma_receive_process_status_type emac_dma_receive_status_get(void) +{ + switch(EMAC_DMA->sts_bit.rs) + { + case EMAC_DMA_RX_RESET_STOP_COMMAND: + { + return EMAC_DMA_RX_RESET_STOP_COMMAND; + } + + case EMAC_DMA_RX_FETCH_DESCRIPTOR: + { + return EMAC_DMA_RX_FETCH_DESCRIPTOR; + } + + case EMAC_DMA_RX_WAITING_PACKET: + { + return EMAC_DMA_RX_WAITING_PACKET; + } + + case EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE: + { + return EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE; + } + + case EMAC_DMA_RX_CLOSE_DESCRIPTOR: + { + return EMAC_DMA_RX_CLOSE_DESCRIPTOR; + } + + case EMAC_DMA_RX_FIFO_TO_HOST: + { + return EMAC_DMA_RX_FIFO_TO_HOST; + } + } + + return EMAC_DMA_RX_RESET_STOP_COMMAND; +} + +/** + * @brief get transmit dma process status + * @param none + * @retval every situation it describe in RM + * this parameter can be one of the following values: + * - EMAC_DMA_TX_RESET_STOP_COMMAND + * - EMAC_DMA_TX_FETCH_DESCRIPTOR + * - EMAC_DMA_TX_WAITING_FOR_STATUS + * - EMAC_DMA_TX_HOST_TO_FIFO + * - EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE + * - EMAC_DMA_TX_CLOSE_DESCRIPTOR + */ +emac_dma_transmit_process_status_type emac_dma_transmit_status_get(void) +{ + switch(EMAC_DMA->sts_bit.ts) + { + case EMAC_DMA_TX_RESET_STOP_COMMAND: + { + return EMAC_DMA_TX_RESET_STOP_COMMAND; + } + + case EMAC_DMA_TX_FETCH_DESCRIPTOR: + { + return EMAC_DMA_TX_FETCH_DESCRIPTOR; + } + + case EMAC_DMA_TX_WAITING_FOR_STATUS: + { + return EMAC_DMA_TX_WAITING_FOR_STATUS; + } + + case EMAC_DMA_TX_HOST_TO_FIFO: + { + return EMAC_DMA_TX_HOST_TO_FIFO; + } + + case EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE: + { + return EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE; + } + + case EMAC_DMA_TX_CLOSE_DESCRIPTOR: + { + return EMAC_DMA_TX_CLOSE_DESCRIPTOR; + } + } + + return EMAC_DMA_TX_RESET_STOP_COMMAND; +} + +/** + * @brief set dma operations + * @param ops: operations of dma + * this parameter can be one of the following values: + * - EMAC_DMA_OPS_START_STOP_RECEIVE + * - EMAC_DMA_OPS_SECOND_FRAME + * - EMAC_DMA_OPS_FORWARD_UNDERSIZED + * - EMAC_DMA_OPS_FORWARD_ERROR + * - EMAC_DMA_OPS_START_STOP_TRANSMIT + * - EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO + * - EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD + * - EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE + * - EMAC_DMA_OPS_RECEIVE_STORE_FORWARD + * - EMAC_DMA_OPS_DROP_ERROR_DISABLE + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_operations_set(emac_dma_operations_type ops, confirm_state new_state) +{ + __IO uint32_t temp = 0; + switch(ops) + { + case EMAC_DMA_OPS_START_STOP_RECEIVE: + { + EMAC_DMA->opm_bit.ssr = new_state; + break; + } + + case EMAC_DMA_OPS_SECOND_FRAME: + { + EMAC_DMA->opm_bit.osf = new_state; + break; + } + + case EMAC_DMA_OPS_FORWARD_UNDERSIZED: + { + EMAC_DMA->opm_bit.fugf = new_state; + break; + } + + case EMAC_DMA_OPS_FORWARD_ERROR: + { + EMAC_DMA->opm_bit.fef = new_state; + break; + } + + case EMAC_DMA_OPS_START_STOP_TRANSMIT: + { + EMAC_DMA->opm_bit.sstc = new_state; + break; + } + + case EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO: + { + EMAC_DMA->opm_bit.ftf = new_state; + temp = EMAC_DMA->opm; + emac_delay(1); + EMAC_DMA->opm = temp; + break; + } + + case EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD: + { + EMAC_DMA->opm_bit.tsf = new_state; + break; + } + + case EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE: + { + EMAC_DMA->opm_bit.dfrf = new_state; + break; + } + + case EMAC_DMA_OPS_RECEIVE_STORE_FORWARD: + { + EMAC_DMA->opm_bit.rsf = new_state; + break; + } + + case EMAC_DMA_OPS_DROP_ERROR_DISABLE: + { + EMAC_DMA->opm_bit.dt = new_state; + break; + } + } +} + +/** + * @brief set receive dma threshold + * @param value: receive threshold + * this parameter can be one of the following values: + * - EMAC_DMA_RX_THRESHOLD_64_BYTES + * - EMAC_DMA_RX_THRESHOLD_32_BYTES + * - EMAC_DMA_RX_THRESHOLD_96_BYTES + * - EMAC_DMA_RX_THRESHOLD_128_BYTES + * @retval none + */ +void emac_dma_receive_threshold_set(emac_dma_receive_threshold_type value) +{ + EMAC_DMA->opm_bit.rtc = value; +} + +/** + * @brief set transmit dma threshold + * @param value: transmit threshold + * this parameter can be one of the following values: + * - EMAC_DMA_TX_THRESHOLD_64_BYTES + * - EMAC_DMA_TX_THRESHOLD_128_BYTES + * - EMAC_DMA_TX_THRESHOLD_192_BYTES + * - EMAC_DMA_TX_THRESHOLD_256_BYTES + * - EMAC_DMA_TX_THRESHOLD_40_BYTES + * - EMAC_DMA_TX_THRESHOLD_32_BYTES + * - EMAC_DMA_TX_THRESHOLD_24_BYTES + * - EMAC_DMA_TX_THRESHOLD_16_BYTES + * @retval none + */ +void emac_dma_transmit_threshold_set(emac_dma_transmit_threshold_type value) +{ + EMAC_DMA->opm_bit.ttc = value; +} + +/** + * @brief enable dma interrupt + * @param it: interrupt type + * this parameter can be one of the following values: + * - EMAC_DMA_INTERRUPT_TX + * - EMAC_DMA_INTERRUPT_TX_STOP + * - EMAC_DMA_INTERRUPT_TX_UNAVAILABLE + * - EMAC_DMA_INTERRUPT_TX_JABBER + * - EMAC_DMA_INTERRUPT_RX_OVERFLOW + * - EMAC_DMA_INTERRUPT_TX_UNDERFLOW + * - EMAC_DMA_INTERRUPT_RX + * - EMAC_DMA_INTERRUPT_RX_UNAVAILABLE + * - EMAC_DMA_INTERRUPT_RX_STOP + * - EMAC_DMA_INTERRUPT_RX_TIMEOUT + * - EMAC_DMA_INTERRUPT_TX_EARLY + * - EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR + * - EMAC_DMA_INTERRUPT_RX_EARLY + * - EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY + * - EMAC_DMA_INTERRUPT_NORMAL_SUMMARY + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_interrupt_enable(emac_dma_interrupt_type it, confirm_state new_state) +{ + switch(it) + { + case EMAC_DMA_INTERRUPT_TX: + { + EMAC_DMA->ie_bit.tie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_STOP: + { + EMAC_DMA->ie_bit.tse = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_UNAVAILABLE: + { + EMAC_DMA->ie_bit.tue = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_JABBER: + { + EMAC_DMA->ie_bit.tje = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_OVERFLOW: + { + EMAC_DMA->ie_bit.ove = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_UNDERFLOW: + { + EMAC_DMA->ie_bit.une = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX: + { + EMAC_DMA->ie_bit.rie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_UNAVAILABLE: + { + EMAC_DMA->ie_bit.rbue = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_STOP: + { + EMAC_DMA->ie_bit.rse = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_TIMEOUT: + { + EMAC_DMA->ie_bit.rwte = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_EARLY: + { + EMAC_DMA->ie_bit.eie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR: + { + EMAC_DMA->ie_bit.fbee = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_EARLY: + { + EMAC_DMA->ie_bit.ere = new_state; + break; + } + case EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY: + { + EMAC_DMA->ie_bit.aie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_NORMAL_SUMMARY: + { + EMAC_DMA->ie_bit.nie = new_state; + break; + } + } +} + +/** + * @brief get missed frames by the controller + * @param none + * @retval missed frames by the controller + */ +uint16_t emac_dma_controller_missing_frame_get(void) +{ + uint16_t number = EMAC_DMA->mfbocnt_bit.mfc; + return number; +} + +/** + * @brief get overflow bit for missed frame counter + * @param none + * @retval overflow bit for missed frame counter + */ +uint8_t emac_dma_missing_overflow_bit_get(void) +{ + uint8_t number = EMAC_DMA->mfbocnt_bit.obmfc; + return number; +} + +/** + * @brief get missed frames by the application + * @param none + * @retval missed frames by the application + */ +uint16_t emac_dma_application_missing_frame_get(void) +{ + uint16_t number = EMAC_DMA->mfbocnt_bit.ofc; + return number; +} + +/** + * @brief get overflow bit for FIFO overflow counter + * @param none + * @retval overflow bit for FIFO overflow counter + */ +uint8_t emac_dma_fifo_overflow_bit_get(void) +{ + uint8_t number = EMAC_DMA->mfbocnt_bit.obfoc; + return number; +} + +/** + * @brief get overflow bit for FIFO overflow counter + * @param transfer type: receive/transmit type + * this parameter can be one of the following values: + * - EMAC_DMA_TX_DESCRIPTOR + * - EMAC_DMA_RX_DESCRIPTOR + * - EMAC_DMA_TX_BUFFER + * - EMAC_DMA_RX_BUFFER + * @retval memory address + */ +uint32_t emac_dma_tansfer_address_get(emac_dma_transfer_address_type transfer_type) +{ + uint32_t address = 0; + + switch(transfer_type) + { + case EMAC_DMA_TX_DESCRIPTOR: + { + address = EMAC_DMA->ctd_bit.htdap; + break; + } + case EMAC_DMA_RX_DESCRIPTOR: + { + address = EMAC_DMA->crd_bit.hrdap; + break; + } + case EMAC_DMA_TX_BUFFER: + { + address = EMAC_DMA->ctbaddr_bit.htbap; + break; + } + case EMAC_DMA_RX_BUFFER: + { + address = EMAC_DMA->crbaddr_bit.hrbap; + break; + } + } + return address; +} + +/** + * @brief reset all counter + * @param none + * @retval none + */ +void emac_mmc_counter_reset(void) +{ + EMAC_MMC->ctrl_bit.rc = TRUE; +} + +/** + * @brief counter stop counting from zero when it reaches maximum + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_rollover_stop(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.scr = new_state; +} + +/** + * @brief enable reset on read + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_reset_on_read_enable(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.rr = new_state; +} + +/** + * @brief freeze mmc counter + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_counter_freeze(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.fmc = new_state; +} + +/** + * @brief interupt status of received frames + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_mmc_received_status_get(uint32_t flag) +{ + if(EMAC_MMC->ri & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief interupt status of transmit frames + * @param transmit_type: transmit type. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_mmc_transmit_status_get(uint32_t flag) +{ + if(EMAC_MMC->ti & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief mask received mmc interrupt + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_received_interrupt_mask_set(uint32_t flag, confirm_state new_state) +{ + switch(flag) + { + case MMC_RX_CRC_ERROR: + { + EMAC_MMC->rim_bit.rcefcim = new_state; + break; + } + case MMC_RX_ALIGN_ERROR: + { + EMAC_MMC->rim_bit.raefacim = new_state; + break; + } + case MMC_RX_GOOD_UNICAST: + { + EMAC_MMC->rim_bit.rugfcim = new_state; + break; + } + } +} + +/** + * @brief mask transmit mmc interrupt + * @param transmit_type: transmit type. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_transmit_interrupt_mask_set(uint32_t flag, confirm_state new_state) +{ + switch(flag) + { + case MMC_TX_SINGLE_COL: + { + EMAC_MMC->tim_bit.tscgfcim = new_state; + break; + } + case MMC_TX_MULTIPLE_COL: + { + EMAC_MMC->tim_bit.tmcgfcim = new_state; + break; + } + case MMC_TX_GOOD_FRAMES: + { + EMAC_MMC->tim_bit.tgfcim = new_state; + break; + } + } +} + +/** + * @brief get good frame numbers as single collision occurs. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @retval good frames + */ +uint32_t emac_mmc_transmit_good_frames_get(uint32_t flag) +{ + uint32_t good_frames = MMC_TX_GOOD_FRAMES; + + switch(flag) + { + case MMC_TX_SINGLE_COL: + { + good_frames = EMAC_MMC->tfscc_bit.tgfscc; + break; + } + case MMC_TX_MULTIPLE_COL: + { + good_frames = EMAC_MMC->tfmscc_bit.tgfmscc; + break; + } + case MMC_TX_GOOD_FRAMES: + { + good_frames = EMAC_MMC->tfcnt_bit.tgfc; + break; + } + } + return good_frames; +} + +/** + * @brief get good frame numbers as single collision occurs. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @retval good frames + */ +uint32_t emac_mmc_received_error_frames_get(uint32_t flag) +{ + uint32_t error_frames = MMC_RX_GOOD_UNICAST; + + switch(flag) + { + case MMC_RX_CRC_ERROR: + { + error_frames = EMAC_MMC->rfcecnt_bit.rfcec; + break; + } + case MMC_RX_ALIGN_ERROR: + { + error_frames = EMAC_MMC->rfaecnt_bit.rfaec; + break; + } + case MMC_RX_GOOD_UNICAST: + { + error_frames = EMAC_MMC->rgufcnt_bit.rgufc; + break; + } + } + return error_frames; +} + +/** + * @brief enable timestamp. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.te = new_state; +} + +/** + * @brief enable timestamp fine update. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_fine_update_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tfcu = new_state; +} + +/** + * @brief initialize timestamp time system. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_system_time_init(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.ti = new_state; +} + +/** + * @brief update timestamp time system. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_system_time_update(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tu = new_state; +} + +/** + * @brief enable timestamp interrupt trigger. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_interrupt_trigger_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tite = new_state; +} + +/** + * @brief update timestamp addend register. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_addend_register_update(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.aru = new_state; +} + +/** + * @brief enable timestamp snapshot for all received frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_received_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.etaf = new_state; +} + +/** + * @brief enable digital rollover. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_subsecond_rollover_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tdbrc = new_state; +} + +/** + * @brief enable packet snooping for version 2. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_psv2_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppv2f = new_state; +} + +/** + * @brief enable snapshot over emac. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_emac_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppef = new_state; +} + +/** + * @brief enable snapshot for ipv6 frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_ipv6_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppfsip6u = new_state; +} + +/** + * @brief enable snapshot for ipv4 frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_ipv4_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppfsip4u = new_state; +} + +/** + * @brief enable snapshot for event message. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_event_message_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.etsfem = new_state; +} + +/** + * @brief enable snapshot for message relevant to master + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_master_event_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.esfmrtm = new_state; +} + +/** + * @brief set clock node type + * @param node: select ptp packets for taking snapshot + * this parameter can be one of the following values: + * - EMAC_PTP_NORMAL_CLOCK + * - EMAC_PTP_BOUNDARY_CLOCK + * - EMAC_PTP_END_TO_END_CLOCK + * - EMAC_PTP_PEER_TO_PEER_CLOCK + * @retval none + */ +void emac_ptp_clock_node_set(emac_ptp_clock_node_type node) +{ + EMAC_PTP->tsctrl_bit.sppfts = node; +} + +/** + * @brief enable ptp frame filtering mac address + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_mac_address_filter_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.emafpff = new_state; +} + +/** + * @brief set subsecond increment value + * @param value: add to subsecond value for every update + * @retval none + */ +void emac_ptp_subsecond_increment_set(uint8_t value) +{ + EMAC_PTP->ssinc_bit.ssiv = value; +} + +/** + * @brief get system time second + * @param none + * @retval system time second + */ +uint32_t emac_ptp_system_second_get(void) +{ + uint32_t second = EMAC_PTP->tsh_bit.ts; + return second; +} + +/** + * @brief get system time subsecond + * @param none + * @retval system time subsecond + */ +uint32_t emac_ptp_system_subsecond_get(void) +{ + uint32_t subsecond = EMAC_PTP->tsl_bit.tss; + return subsecond; +} + +/** + * @brief get system time sign + * @param none + * @retval TRUE or FALSE + */ +confirm_state emac_ptp_system_time_sign_get(void) +{ + if(EMAC_PTP->tsl_bit.ast) + { + return TRUE; + } + else + { + return FALSE; + } +} + +/** + * @brief set system time second + * @param second: system time second + * @retval none + */ +void emac_ptp_system_second_set(uint32_t second) +{ + EMAC_PTP->tshud_bit.ts = second; +} + +/** + * @brief set system time subsecond + * @param subsecond: system time subsecond + * @retval none + */ +void emac_ptp_system_subsecond_set(uint32_t subsecond) +{ + EMAC_PTP->tslud_bit.tss = subsecond; +} + +/** + * @brief set system time sign + * @param sign: TRUE or FALSE. + * @retval none + */ +void emac_ptp_system_time_sign_set(confirm_state sign) +{ + if(sign) + { + EMAC_PTP->tslud_bit.ast = 1; + } + else + { + EMAC_PTP->tslud_bit.ast = 0; + } +} + +/** + * @brief set time stamp addend + * @param value: to achieve time synchronization + * @retval none + */ +void emac_ptp_timestamp_addend_set(uint32_t value) +{ + EMAC_PTP->tsad_bit.tar = value; +} + +/** + * @brief set target time stamp high + * @param value: to set target time second + * @retval none + */ +void emac_ptp_target_second_set(uint32_t value) +{ + EMAC_PTP->tth_bit.ttsr = value; +} + +/** + * @brief set target time stamp low + * @param value: to set target time nanosecond + * @retval none + */ +void emac_ptp_target_nanosecond_set(uint32_t value) +{ + EMAC_PTP->ttl_bit.ttlr = value; +} + +/** + * @brief set target time stamp low + * @param status: type of status + * this parameter can be one of the following values: + * - EMAC_PTP_SECOND_OVERFLOW + * - EMAC_PTP_TARGET_TIME_REACH + * @retval TRUE or FALSE + */ +confirm_state emac_ptp_timestamp_status_get(emac_ptp_timestamp_status_type status) +{ + switch(status) + { + case EMAC_PTP_SECOND_OVERFLOW: + { + if(EMAC_PTP->tssr_bit.tso) + { + return TRUE; + } + else + { + return FALSE; + } + } + case EMAC_PTP_TARGET_TIME_REACH: + { + if(EMAC_PTP->tssr_bit.tttr) + { + return TRUE; + } + else + { + return FALSE; + } + } + } + return FALSE; +} + +/** + * @brief set pps frequency + * @param freq: pps frequency + * this parameter can be one of the following values: + * - EMAC_PTP_PPS_1HZ + * - EMAC_PTP_PPS_2HZ + * - EMAC_PTP_PPS_4HZ + * - EMAC_PTP_PPS_8HZ + * - EMAC_PTP_PPS_16HZ + * - EMAC_PTP_PPS_32HZ + * - EMAC_PTP_PPS_64HZ + * - EMAC_PTP_PPS_128HZ + * - EMAC_PTP_PPS_256HZ + * - EMAC_PTP_PPS_512HZ + * - EMAC_PTP_PPS_1024HZ + * - EMAC_PTP_PPS_2048HZ + * - EMAC_PTP_PPS_4096HZ + * - EMAC_PTP_PPS_8192HZ + * - EMAC_PTP_PPS_16384HZ + * - EMAC_PTP_PPS_32768HZ + * @retval none + */ +void emac_ptp_pps_frequency_set(emac_ptp_pps_control_type freq) +{ + EMAC_PTP->ppscr_bit.pofc = freq; +} + +/** + * @brief this is delay function base on system clock. + * @param delay: delay time + * @retval none + */ +static void emac_delay(uint32_t delay) +{ + __IO uint32_t delay_time = delay * (system_core_clock / 8 / 1000); + do + { + __NOP(); + } + while(delay_time --); +} + +/** + * @brief check whether the specified emac dma flag is set or not. + * @param dma_flag: specifies the emac dma flag to check. + * this parameter can be one of emac dma flag status: + * - EMAC_DMA_TI_FLAG + * - EMAC_DMA_TPS_FLAG + * - EMAC_DMA_TBU_FLAG + * - EMAC_DMA_TJT_FLAG + * - EMAC_DMA_OVF_FLAG + * - EMAC_DMA_UNF_FLAG + * - EMAC_DMA_RI_FLAG + * - EMAC_DMA_RBU_FLAG + * - EMAC_DMA_RPS_FLAG + * - EMAC_DMA_RWT_FLAG + * - EMAC_DMA_ETI_FLAG + * - EMAC_DMA_FBEI_FLAG + * - EMAC_DMA_ERI_FLAG + * - EMAC_DMA_AIS_FLAG + * - EMAC_DMA_NIS_FLAG + * @retval the new state of dma_flag (SET or RESET). + */ +flag_status emac_dma_flag_get(uint32_t dma_flag) +{ + flag_status status = RESET; + + if(EMAC_DMA->sts & dma_flag) + status = SET; + /* return the new state (SET or RESET) */ + return status; +} + +/** + * @brief clear the emac dma flag. + * @param dma_flag: specifies the emac dma flags to clear. + * this parameter can be any combination of the following values: + * - EMAC_DMA_TI_FLAG + * - EMAC_DMA_TPS_FLAG + * - EMAC_DMA_TBU_FLAG + * - EMAC_DMA_TJT_FLAG + * - EMAC_DMA_OVF_FLAG + * - EMAC_DMA_UNF_FLAG + * - EMAC_DMA_RI_FLAG + * - EMAC_DMA_RBU_FLAG + * - EMAC_DMA_RPS_FLAG + * - EMAC_DMA_RWT_FLAG + * - EMAC_DMA_ETI_FLAG + * - EMAC_DMA_FBEI_FLAG + * - EMAC_DMA_ERI_FLAG + * - EMAC_DMA_AIS_FLAG + * - EMAC_DMA_NIS_FLAG + * @retval none + */ +void emac_dma_flag_clear(uint32_t dma_flag) +{ + EMAC_DMA->sts = dma_flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +#endif + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c new file mode 100644 index 0000000000..d09528481d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c @@ -0,0 +1,1571 @@ +/** + ************************************************************************** + * @file at32f435_437_ertc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the ertc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ERTC + * @brief ERTC driver modules + * @{ + */ + +#ifdef ERTC_MODULE_ENABLED + +/** @defgroup ERTC_private_functions + * @{ + */ + +#define ERTC_TIMEOUT ((uint32_t) 0x00360000) + +/** + * @brief number conversion to bcd code. + * @param num: number(0~99) + * @retval bcd code. + */ +uint8_t ertc_num_to_bcd(uint8_t num) +{ + uint8_t bcd_h = 0, bcd_l = 0; + + bcd_h = num / 10; + bcd_l = num % 10; + + return ((uint8_t)(bcd_h << 4) | bcd_l); +} + +/** + * @brief bcd code conversion to number. + * @param bcd: bcd code(0~99). + * @retval number. + */ +uint8_t ertc_bcd_to_num(uint8_t bcd) +{ + return ((((uint8_t)(bcd & (uint8_t)0xF0) >> 4) * 10) + (bcd & (uint8_t)0x0F)); +} + +/** + * @brief enable write protection. + * @param none. + * @retval none + */ +void ertc_write_protect_enable(void) +{ + ERTC->wp = 0xFF; +} + +/** + * @brief disable write protection. + * @param none. + * @retval none + */ +void ertc_write_protect_disable(void) +{ + ERTC->wp = 0xCA; + ERTC->wp = 0x53; +} + +/** + * @brief ertc wait register update finish. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wait_update(void) +{ + uint32_t timeout = ERTC_TIMEOUT * 2; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* clear updf flag */ + ERTC->sts = ~(ERTC_UPDF_FLAG | 0x00000080) | (ERTC->sts_bit.imen << 7); + + /* enable write protection */ + ertc_write_protect_enable(); + + while(ERTC->sts_bit.updf == 0) + { + if(timeout == 0) + { + return ERROR; + } + + timeout--; + } + + return SUCCESS; +} + +/** + * @brief ertc wait flag status. + * @param flag: flag to wait. + * this parameter can be one of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @param status: status to wait. + * this parameter can be one of the following values: + * - SET. + * - RESET. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wait_flag(uint32_t flag, flag_status status) +{ + uint32_t timeout = ERTC_TIMEOUT; + + while(ertc_flag_get(flag) == status) + { + if(timeout == 0) + { + /* enable write protection */ + ertc_write_protect_enable(); + + return ERROR; + } + + timeout--; + } + + return SUCCESS; +} + +/** + * @brief ertc enter init mode. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_init_mode_enter(void) +{ + uint32_t timeout = ERTC_TIMEOUT * 2; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ERTC->sts_bit.imf == 0) + { + /* enter init mode */ + ERTC->sts = 0xFFFFFFFF; + + while(ERTC->sts_bit.imf == 0) + { + if(timeout == 0) + { + /* enable write protection */ + ertc_write_protect_enable(); + + return ERROR; + } + + timeout--; + } + } + + return SUCCESS; +} + +/** + * @brief ertc exit init mode. + * @param none. + * @retval none. + */ +void ertc_init_mode_exit(void) +{ + ERTC->sts = 0xFFFFFF7F; +} + +/** + * @brief ertc reset all register. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_reset(void) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl = (uint32_t)0x00000000; + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* reset register */ + ERTC->time = (uint32_t)0x00000000; + ERTC->date = (uint32_t)0x00002101; + ERTC->ctrl = (uint32_t)0x00000000; + ERTC->div = (uint32_t)0x007F00FF; + ERTC->wat = (uint32_t)0x0000FFFF; + ERTC->ccal = (uint32_t)0x00000000; + ERTC->ala = (uint32_t)0x00000000; + ERTC->alb = (uint32_t)0x00000000; + ERTC->tadj = (uint32_t)0x00000000; + ERTC->scal = (uint32_t)0x00000000; + ERTC->tamp = (uint32_t)0x00000000; + ERTC->alasbs = (uint32_t)0x00000000; + ERTC->albsbs = (uint32_t)0x00000000; + ERTC->sts = (uint32_t)0x00000000; + + /* wait calendar update */ + ertc_wait_update(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief ertc division set. + * @param div_a: division a (0~0x7F). + * @param div_b: division b (0~0x7FFF). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_divider_set(uint16_t div_a, uint16_t div_b) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* config the ertc divider */ + ERTC->div_bit.diva = div_a; + ERTC->div_bit.divb = div_b; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief ertc hour mode set. + * @param mode: hour mode. + * this parameter can be one of the following values: + * - ERTC_HOUR_MODE_24: 24-hour format. + * - ERTC_HOUR_MODE_12: 12-hour format. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_hour_mode_set(ertc_hour_mode_set_type mode) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* write register */ + ERTC->ctrl_bit.hm = mode; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set date. + * @param year: year (0~99). + * @param month: month (1~12). + * @param date: date (1~31). + * @param week: week (1~7). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_date_set(uint8_t year, uint8_t month, uint8_t date, uint8_t week) +{ + ertc_reg_date_type reg; + + reg.date = 0; + + reg.date_bit.y = ertc_num_to_bcd(year); + reg.date_bit.m = ertc_num_to_bcd(month); + reg.date_bit.d = ertc_num_to_bcd(date); + reg.date_bit.wk = week; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* Set the ertc_DR register */ + ERTC->date = reg.date; + + /* exit init mode */ + ertc_init_mode_exit(); + + if(ERTC->ctrl_bit.dren == 0) + { + ertc_wait_update(); + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set time. + * @param hour: hour (0~23). + * @param min: minute (0~59). + * @param sec: second (0~59). + * @param ampm: hour mode. + * this parameter can be one of the following values: + * - ERTC_24H: 24-hour format. + * - ERTC_AM: 12-hour format, ante meridiem. + * - ERTC_PM: 12-hour format, post meridiem. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_time_set(uint8_t hour, uint8_t min, uint8_t sec, ertc_am_pm_type ampm) +{ + ertc_reg_time_type reg; + + reg.time = 0; + + reg.time_bit.h = ertc_num_to_bcd(hour); + reg.time_bit.m = ertc_num_to_bcd(min); + reg.time_bit.s = ertc_num_to_bcd(sec); + reg.time_bit.ampm = ampm; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + ERTC->time = reg.time; + + /* exit init mode */ + ertc_init_mode_exit(); + + if(ERTC->ctrl_bit.dren == 0) + { + ertc_wait_update(); + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief get calendar + * @param time: ertc time. + * @retval none. + */ +void ertc_calendar_get(ertc_time_type* time) +{ + ertc_reg_time_type reg_tm; + ertc_reg_date_type reg_dt; + + UNUSED(ERTC->sts); + + reg_tm.time = ERTC->time; + reg_dt.date = ERTC->date; + + time->hour = ertc_bcd_to_num(reg_tm.time_bit.h); + time->min = ertc_bcd_to_num(reg_tm.time_bit.m); + time->sec = ertc_bcd_to_num(reg_tm.time_bit.s); + time->ampm = (ertc_am_pm_type)reg_tm.time_bit.ampm; + + time->year = ertc_bcd_to_num(reg_dt.date_bit.y); + time->month = ertc_bcd_to_num(reg_dt.date_bit.m); + time->day = ertc_bcd_to_num(reg_dt.date_bit.d); + time->week = reg_dt.date_bit.wk; +} + +/** + * @brief get current sub second. + * @param none. + * @retval sub second. + */ +uint32_t ertc_sub_second_get(void) +{ + uint32_t reg = 0; + + reg = ERTC->sbs; + + (void) (ERTC->date); + + return (reg); +} + +/** + * @brief set which bits are irrelevant to the alarm match. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param mask: select which bits are irrelevant to the alarm match. + * this parameter can be one of the following values: + * - ERTC_ALARM_MASK_NONE: match all. + * - ERTC_ALARM_MASK_SEC: don't match seconds. + * - ERTC_ALARM_MASK_MIN: don't match minute. + * - ERTC_ALARM_MASK_HOUR: don't match hour. + * - ERTC_ALARM_MASK_DATE_WEEK: don't match date or week. + * - ERTC_ALARM_MASK_ALL: don't match all. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_mask_set(ertc_alarm_type alarm_x, uint32_t mask) +{ + uint32_t reg; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + reg = ERTC->ala; + + reg &= ~ERTC_ALARM_MASK_ALL; + reg |= mask; + + ERTC->ala= reg; + } + else + { + reg = ERTC->alb; + + reg &= ~ERTC_ALARM_MASK_ALL; + reg |= mask; + + ERTC->alb= reg; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief alarm week or date mode select. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param wk: week or date mode select. + * this parameter can be one of the following values: + * - ERTC_SLECT_DATE: slect date mode. + * - ERTC_SLECT_WEEK: slect week mode. + * @retval none. + */ +void ertc_alarm_week_date_select(ertc_alarm_type alarm_x, ertc_week_date_select_type wk) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ala_bit.wksel = wk; + } + else + { + ERTC->alb_bit.wksel = wk; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set alarm. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param week_day: week or date. + * - week: 1~7. + * - date: 1~31. + * @param hour: hour (0~23). + * @param min: minute (0~59). + * @param sec: second (0~59). + * @param ampm: hour mode. + * this parameter can be one of the following values: + * - ERTC_24H: 24-hour format. + * - ERTC_AM: 12-hour format, ante meridiem. + * - ERTC_PM: 12-hour format, post meridiem. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_set(ertc_alarm_type alarm_x, uint8_t week_date, uint8_t hour, uint8_t min, uint8_t sec, ertc_am_pm_type ampm) +{ + ertc_reg_alarm_type reg; + + if(alarm_x == ERTC_ALA) + { + reg.ala = ERTC->ala; + } + else + { + reg.ala = ERTC->alb; + } + + reg.ala_bit.d = ertc_num_to_bcd(week_date); + reg.ala_bit.h = ertc_num_to_bcd(hour); + reg.ala_bit.m = ertc_num_to_bcd(min); + reg.ala_bit.s = ertc_num_to_bcd(sec); + reg.ala_bit.ampm = ampm; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ala= reg.ala; + } + else + { + ERTC->alb = reg.ala; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set alarm sub second. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param value: sub second value. + * @param mask: sub second mask. + * this parameter can be one of the following values: + * - ERTC_ALARM_SBS_MASK_ALL: do not match the sub-second. + * - ERTC_ALARM_SBS_MASK_14_1: only compare bit [0]. + * - ERTC_ALARM_SBS_MASK_14_2: only compare bit [1:0]. + * - ERTC_ALARM_SBS_MASK_14_3: only compare bit [2:0]. + * - ERTC_ALARM_SBS_MASK_14_4: only compare bit [3:0]. + * - ERTC_ALARM_SBS_MASK_14_5: only compare bit [4:0]. + * - ERTC_ALARM_SBS_MASK_14_6: only compare bit [5:0]. + * - ERTC_ALARM_SBS_MASK_14_7: only compare bit [6:0]. + * - ERTC_ALARM_SBS_MASK_14_8: only compare bit [7:0]. + * - ERTC_ALARM_SBS_MASK_14_9: only compare bit [8:0]. + * - ERTC_ALARM_SBS_MASK_14_10: only compare bit [9:0]. + * - ERTC_ALARM_SBS_MASK_14_11: only compare bit [10:0]. + * - ERTC_ALARM_SBS_MASK_14_12: only compare bit [11:0]. + * - ERTC_ALARM_SBS_MASK_14_13: only compare bit [12:0]. + * - ERTC_ALARM_SBS_MASK_14: only compare bit [13:0]. + * - ERTC_ALARM_SBS_MASK_NONE: compare bit [14:0]. + * @retval none. + */ +void ertc_alarm_sub_second_set(ertc_alarm_type alarm_x, uint32_t value, ertc_alarm_sbs_mask_type mask) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->alasbs_bit.sbsmsk = mask; + ERTC->alasbs_bit.sbs = value; + } + else + { + ERTC->albsbs_bit.sbsmsk = mask; + ERTC->albsbs_bit.sbs = value; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable alarm clock. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_alarm_enable(ertc_alarm_type alarm_x, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ctrl_bit.alaen = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_ALAWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + } + else + { + ERTC->ctrl_bit.alben = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_ALBWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief get alarm value. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_get(ertc_alarm_type alarm_x, ertc_alarm_value_type* alarm) +{ + ertc_reg_alarm_type reg; + + reg.ala = 0; + + if(alarm_x == ERTC_ALA) + { + reg.ala = ERTC->ala; + } + else + { + reg.ala = ERTC->alb; + } + + alarm->day = ertc_bcd_to_num(reg.ala_bit.d); + alarm->week = ertc_bcd_to_num(reg.ala_bit.d); + alarm->hour = ertc_bcd_to_num(reg.ala_bit.h); + alarm->min = ertc_bcd_to_num(reg.ala_bit.m); + alarm->sec = ertc_bcd_to_num(reg.ala_bit.s); + alarm->ampm = (ertc_am_pm_type)reg.ala_bit.ampm; + alarm->week_date_sel = reg.ala_bit.wksel; + alarm->mask = reg.ala & ERTC_ALARM_MASK_ALL; +} + +/** + * @brief get alarm sub second. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @retval sub second. + */ +uint32_t ertc_alarm_sub_second_get(ertc_alarm_type alarm_x) +{ + if(alarm_x == ERTC_ALA) + { + return (ERTC->alasbs_bit.sbs); + } + else + { + return (ERTC->albsbs_bit.sbs); + } +} + +/** + * @brief set wakeup timer clock. + * @param clock: wakeup timer clock source. + * this parameter can be one of the following values: + * - ERTC_WAT_CLK_ERTCCLK_DIV16: ERTC_CLK / 16. + * - ERTC_WAT_CLK_ERTCCLK_DIV8: ERTC_CLK / 8. + * - ERTC_WAT_CLK_ERTCCLK_DIV4: ERTC_CLK / 4. + * - ERTC_WAT_CLK_ERTCCLK_DIV2: ERTC_CLK / 2. + * - ERTC_WAT_CLK_CK_B_16BITS: CK_B, wakeup counter = ERTC_WAT + * - ERTC_WAT_CLK_CK_B_17BITS: CK_B, wakeup counter = ERTC_WAT + 65535. + * @retval none. + */ +void ertc_wakeup_clock_set(ertc_wakeup_clock_type clock) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.watclk = clock; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set wakeup counter. + * @param counter: wakeup counter(0~65535). + * @retval none. + */ +void ertc_wakeup_counter_set(uint32_t counter) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->wat_bit.val = counter; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get wakeup counter. + * @param none. + * @retval wakeup counter. + */ +uint16_t ertc_wakeup_counter_get(void) +{ + return ERTC->wat_bit.val; +} + +/** + * @brief enable or disable wakeup timer. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wakeup_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.waten = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_WATWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief config the smooth calibration. + * @param period: calibration period. + * this parameter can be one of the following values: + * - ERTC_SMOOTH_CAL_PERIOD_32: 32 second calibration period. + * - ERTC_SMOOTH_CAL_PERIOD_16: 16 second calibration period. + * - ERTC_SMOOTH_CAL_PERIOD_8: 8 second calibration period. + * @param clk_add: add clock. + * this parameter can be one of the following values: + * - ERTC_SMOOTH_CAL_CLK_ADD_0: do not increase clock. + * - ERTC_SMOOTH_CAL_CLK_ADD_512: add 512 clocks. + * @param clk_dec: decrease clock(0~511). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_smooth_calibration_config(ertc_smooth_cal_period_type period, ertc_smooth_cal_clk_add_type clk_add, uint32_t clk_dec) +{ + ertc_reg_scal_type reg; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ertc_wait_flag(ERTC_CALUPDF_FLAG, SET) != SUCCESS) + { + return ERROR; + } + + reg.scal = 0; + + switch (period) + { + case ERTC_SMOOTH_CAL_PERIOD_32: + break; + case ERTC_SMOOTH_CAL_PERIOD_16: + reg.scal_bit.cal16 = 1; + break; + case ERTC_SMOOTH_CAL_PERIOD_8: + reg.scal_bit.cal8 = 1; + break; + default: + break; + } + + reg.scal_bit.add = clk_add; + reg.scal_bit.dec = clk_dec; + + ERTC->scal = reg.scal; + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set the coarse digital calibration. + * @param dir: calibration direction. + * this parameter can be one of the following values: + * - ERTC_CAL_DIR_POSITIVE: positive calibration. + * - ERTC_CAL_DIR_NEGATIVE: negative calibration. + * @param value: calibration value(0~31). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_coarse_calibration_set(ertc_cal_direction_type dir, uint32_t value) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() == ERROR) + { + return ERROR; + } + + ERTC->ccal_bit.caldir = dir; + + ERTC->ccal_bit.calval = value; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief enable or disable coarse calibration. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_coarse_calibration_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() == ERROR) + { + return ERROR; + } + + ERTC->ctrl_bit.ccalen = new_state; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief calibration output source select. + * @param output: output source. + * this parameter can be one of the following values: + * - ERTC_CAL_OUTPUT_512HZ: output 512 hz. + * - ERTC_CAL_OUTPUT_1HZ: output 1 hz. + * @retval none. + */ +void ertc_cal_output_select(ertc_cal_output_select_type output) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.calosel = output; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable calibration output. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_cal_output_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.caloen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief adjust the time. + * @param add1s: second operation. + * this parameter can be one of the following values: + * - ERTC_TIME_ADD_NONE: none operation. + * - ERTC_TIME_ADD_1S: add 1 second. + * @param decsbs: decrease sub second(0~0x7FFF). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_time_adjust(ertc_time_adjust_type add1s, uint32_t decsbs) +{ + ertc_reg_tadj_type reg; + + reg.tadj = 0; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ertc_wait_flag(ERTC_TADJF_FLAG, SET) != SUCCESS) + { + return ERROR; + } + + /* check if the reference clock detection is disabled */ + if(ERTC->ctrl_bit.rcden == 0) + { + reg.tadj_bit.add1s = add1s; + reg.tadj_bit.decsbs = decsbs; + + ERTC->tadj = reg.tadj; + + if(ertc_wait_update() == ERROR) + { + return ERROR; + } + } + else + { + return ERROR; + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief config the daylight saving time. + * @param operation: time adjust. + * this parameter can be one of the following values: + * - ERTC_DST_ADD_1H: add 1 hour. + * - ERTC_DST_DEC_1H: dec 1 hour. + * @param save: operation save. + * this parameter can be one of the following values: + * - ERTC_DST_SAVE_0: set the bpr register value to 0. + * - ERTC_DST_SAVE_1: set the bpr register value to 1. + * @retval none. + */ +void ertc_daylight_set(ertc_dst_operation_type operation, ertc_dst_save_type save) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(operation == ERTC_DST_ADD_1H) + { + ERTC->ctrl_bit.add1h = 1; + } + else + { + ERTC->ctrl_bit.dec1h = 1; + } + + ERTC->ctrl_bit.bpr = save; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get the bpr value. + * @param none. + * @retval bpr value. + */ +uint8_t ertc_daylight_bpr_get(void) +{ + return ERTC->ctrl_bit.bpr; +} + +/** + * @brief enable or disable refer clock detect. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_refer_clock_detect_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* write register */ + ERTC->ctrl_bit.rcden = new_state; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief enable or disable direct read mode. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_direct_read_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.dren = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the output mode. + * @param source: output source. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_DISABLE: diable output. + * - ERTC_OUTPUT_ALARM_A: output alarm a event. + * - ERTC_OUTPUT_ALARM_B: output alarm b event. + * - ERTC_OUTPUT_WAKEUP: output wakeup event. + * @param polarity: output polarity. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_POLARITY_HIGH: when the event occurs, the output is high. + * - ERTC_OUTPUT_POLARITY_LOW: when the event occurs, the output is low. + * @param type: output type. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_TYPE_OPEN_DRAIN: open drain output. + * - ERTC_OUTPUT_TYPE_PUSH_PULL: push pull output. + * @retval none. + */ +void ertc_output_set(ertc_output_source_type source, ertc_output_polarity_type polarity, ertc_output_type type) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.outp = polarity; + + ERTC->tamp_bit.outtype = type; + + ERTC->ctrl_bit.outsel = source; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief timestamp detection pin selection. + * @param pin: data register + * this parameter can be one of the following values: + * - ERTC_PIN_PC13: pc13 is used as timestamp detection pin. + * - ERTC_PIN_PA0: pa0 is used as timestamp detection pin. + * @retval data value. + */ +void ertc_timestamp_pin_select(ertc_pin_select_type pin) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tspin = pin; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the timestamp valid edge. + * @param edge: calibration period. + * this parameter can be one of the following values: + * - ERTC_TIMESTAMP_EDGE_RISING : rising edge trigger. + * - ERTC_TIMESTAMP_EDGE_FALLING: falling edge trigger. + * @retval none. + */ +void ertc_timestamp_valid_edge_set(ertc_timestamp_valid_edge_type edge) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.tsedg = edge; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable timestamp. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_timestamp_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.tsen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get the timestamp. + * @param time: time. + * @param date: date. + * @retval none. + */ +void ertc_timestamp_get(ertc_time_type* time) +{ + ertc_reg_tstm_type tmtime; + ertc_reg_tsdt_type tmdate; + + tmtime.tstm = ERTC->tstm; + tmdate.tsdt = ERTC->tsdt; + + time->year = 0; + time->month = ertc_bcd_to_num(tmdate.tsdt_bit.m); + time->day = ertc_bcd_to_num(tmdate.tsdt_bit.d); + time->week = ertc_bcd_to_num(tmdate.tsdt_bit.wk); + time->hour = ertc_bcd_to_num(tmtime.tstm_bit.h); + time->min = ertc_bcd_to_num(tmtime.tstm_bit.m); + time->sec = ertc_bcd_to_num(tmtime.tstm_bit.s); + time->ampm = (ertc_am_pm_type)tmtime.tstm_bit.ampm; +} + +/** + * @brief get the timestamp sub second. + * @param none. + * @retval timestamp sub second. + */ +uint32_t ertc_timestamp_sub_second_get(void) +{ + return ERTC->tssbs_bit.sbs; +} + +/** + * @brief tamper 1 detection pin selection. + * @param pin: data register + * this parameter can be one of the following values: + * - ERTC_PIN_PC13: pc13 is used as tamper 1 detection pin. + * - ERTC_PIN_PA0: pa0 is used as tamper 1 detection pin. + * @retval data value. + */ +void ertc_tamper_1_pin_select(ertc_pin_select_type pin) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tp1pin = pin; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable tamper pin pull up. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_pull_up_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tppu = !new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper pin pre-charge time. + * @param precharge: tamper detection pre-charge time + * this parameter can be one of the following values: + * - ERTC_TAMPER_PR_1_ERTCCLK: pre-charge time is 1 ERTC_CLK. + * - ERTC_TAMPER_PR_2_ERTCCLK: pre-charge time is 2 ERTC_CLK. + * - ERTC_TAMPER_PR_4_ERTCCLK: pre-charge time is 4 ERTC_CLK. + * - ERTC_TAMPER_PR_8_ERTCCLK: pre-charge time is 8 ERTC_CLK. + * @retval none. + */ +void ertc_tamper_precharge_set(ertc_tamper_precharge_type precharge) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tppr = precharge; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper filter time. + * @param filter: tamper filter. + * this parameter can be one of the following values: + * - ERTC_TAMPER_FILTER_DISABLE: disable filter function. + * - ERTC_TAMPER_FILTER_2: 2 consecutive samples arw valid, effective tamper event. + * - ERTC_TAMPER_FILTER_4: 4 consecutive samples arw valid, effective tamper event. + * - ERTC_TAMPER_FILTER_8: 8 consecutive samples arw valid, effective tamper event. + * @retval none. + */ +void ertc_tamper_filter_set(ertc_tamper_filter_type filter) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tpflt = filter; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper detection frequency. + * @param freq: tamper detection frequency. + * this parameter can be one of the following values: + * - ERTC_TAMPER_FREQ_DIV_32768: ERTC_CLK / 32768. + * - ERTC_TAMPER_FREQ_DIV_16384: ERTC_CLK / 16384. + * - ERTC_TAMPER_FREQ_DIV_8192: ERTC_CLK / 8192. + * - ERTC_TAMPER_FREQ_DIV_4096: ERTC_CLK / 4096. + * - ERTC_TAMPER_FREQ_DIV_2048: ERTC_CLK / 2048. + * - ERTC_TAMPER_FREQ_DIV_1024: ERTC_CLK / 1024. + * - ERTC_TAMPER_FREQ_DIV_512: ERTC_CLK / 512. + * - ERTC_TAMPER_FREQ_DIV_256: ERTC_CLK / 256. + * @retval none. + */ +void ertc_tamper_detect_freq_set(ertc_tamper_detect_freq_type freq) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tpfreq = freq; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper trigger. + * @param tamper_x: select the tamper. + * this parameter can be one of the following values: + * - ERTC_TAMPER_1: tamper 1. + * - ERTC_TAMPER_2: tamper 2. + * @param trigger: tamper valid edge. + * this parameter can be one of the following values: + * - ERTC_TAMPER_EDGE_RISING: rising gedge. + * - ERTC_TAMPER_EDGE_FALLING: falling gedge. + * - ERTC_TAMPER_EDGE_LOW: low level. + * - ERTC_TAMPER_EDGE_HIGH: high level. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_tamper_valid_edge_set(ertc_tamper_select_type tamper_x, ertc_tamper_valid_edge_type trigger) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(tamper_x == ERTC_TAMPER_1) + { + ERTC->tamp_bit.tp1edg = trigger; + } + else + { + ERTC->tamp_bit.tp2edg = trigger; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable trigger timestamp when tamper event occurs. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_timestamp_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tptsen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable tamper. + * @param tamper_x: select the tamper. + * this parameter can be one of the following values: + * - ERTC_TAMPER_1: tamper 1. + * - ERTC_TAMPER_2: tamper 2. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_enable(ertc_tamper_select_type tamper_x, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(tamper_x == ERTC_TAMPER_1) + { + ERTC->tamp_bit.tp1en = new_state; + } + else + { + ERTC->tamp_bit.tp2en = new_state; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable interrupt. + * @param source: interrupts sources + * this parameter can be any combination of the following values: + * - ERTC_TP_INT: tamper interrupt. + * - ERTC_ALA_INT: alarm a interrupt. + * - ERTC_ALB_INT: alarm b interrupt. + * - ERTC_WAT_INT: wakeup timer interrupt. + * - ERTC_TS_INT: timestamp interrupt. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_interrupt_enable(uint32_t source, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(source & ERTC_TP_INT) + { + if(new_state != FALSE) + { + ERTC->tamp |= ERTC_TP_INT; + } + else + { + ERTC->tamp &= ~ERTC_TP_INT; + } + + source &= ~ERTC_TP_INT; + } + + if(new_state != FALSE) + { + ERTC->ctrl |= source; + } + else + { + ERTC->ctrl &= ~source; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get interrupt status + * @param source + * this parameter can be one of the following values: + * - ERTC_TP_INT: tamper interrupt. + * - ERTC_ALA_INT: alarm a interrupt. + * - ERTC_ALB_INT: alarm b interrupt. + * - ERTC_WAT_INT: wakeup timer interrupt. + * - ERTC_TS_INT: timestamp interrupt. + * @retval flag_status (SET or RESET) + */ +flag_status ertc_interrupt_get(uint32_t source) +{ + if(source & ERTC_TP_INT) + { + if((ERTC->tamp & ERTC_TP_INT) != RESET) + { + return SET; + } + else + { + return RESET; + } + } + + if((ERTC->ctrl & source) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief get flag status. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_INITF_FLAG: calendar initialization flag. + * - ERTC_UPDF_FLAG: calendar update flag. + * - ERTC_IMF_FLAG: enter initialization mode flag. + * - ERTC_ALAF_FLAG: alarm clock a flag. + * - ERTC_ALBF_FLAG: alarm clock b flag. + * - ERTC_WATF_FLAG: wakeup timer flag. + * - ERTC_TSF_FLAG: timestamp flag. + * - ERTC_TSOF_FLAG: timestamp overflow flag. + * - ERTC_TP1F_FLAG: tamper detection 1 flag. + * - ERTC_TP2F_FLAG: tamper detection 2 flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @retval the new state of flag (SET or RESET). + */ +flag_status ertc_flag_get(uint32_t flag) +{ + if((ERTC->sts & flag) != (uint32_t)RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear flag status + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_INITF_FLAG: calendar initialization flag. + * - ERTC_UPDF_FLAG: calendar update flag. + * - ERTC_IMF_FLAG: enter initialization mode flag. + * - ERTC_ALAF_FLAG: alarm clock a flag. + * - ERTC_ALBF_FLAG: alarm clock b flag. + * - ERTC_WATF_FLAG: wakeup timer flag. + * - ERTC_TSF_FLAG: timestamp flag. + * - ERTC_TSOF_FLAG: timestamp overflow flag. + * - ERTC_TP1F_FLAG: tamper detection 1 flag. + * - ERTC_TP2F_FLAG: tamper detection 2 flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @retval none + */ +void ertc_flag_clear(uint32_t flag) +{ + ERTC->sts = ~(flag | 0x00000080) | (ERTC->sts_bit.imen << 7); +} + +/** + * @brief write data to the bpr register. + * @param dt: data register + * this parameter can be one of the following values: + * - ERTC_DT1 + * - ERTC_DT2 + * - ... + * - ERTC_DT19 + * - ERTC_DT20 + * @param data: data to be write. + * @retval none. + */ +void ertc_bpr_data_write(ertc_dt_type dt, uint32_t data) +{ + __IO uint32_t reg = 0; + + reg = ERTC_BASE + 0x50 + (dt * 4); + + /* disable write protection */ + ertc_write_protect_disable(); + + *(__IO uint32_t *)reg = data; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief read data from bpr register. + * @param dt: data register + * this parameter can be one of the following values: + * - ERTC_DT1 + * - ERTC_DT2 + * - ... + * - ERTC_DT19 + * - ERTC_DT20 + * @retval data value. + */ +uint32_t ertc_bpr_data_read(ertc_dt_type dt) +{ + __IO uint32_t reg = 0; + + reg = ERTC_BASE + 0x50 + (dt * 4); + + return (*(__IO uint32_t *)reg); +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c new file mode 100644 index 0000000000..31d55c0aff --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c @@ -0,0 +1,236 @@ +/** + ************************************************************************** + * @file at32f435_437_exint.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the exint firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EXINT + * @brief EXINT driver modules + * @{ + */ + +#ifdef EXINT_MODULE_ENABLED + +/** @defgroup EXINT_private_functions + * @{ + */ + +/** + * @brief exint reset + * @param none + * @retval none + */ +void exint_reset(void) +{ + EXINT->inten = 0x00000000; + EXINT->polcfg1 = 0x00000000; + EXINT->polcfg2 = 0x00000000; + EXINT->evten = 0x00000000; + EXINT->intsts = 0x007FFFFF; +} + +/** + * @brief exint default para init + * @param exint_struct + * - to the structure of exint_init_type + * @retval none + */ +void exint_default_para_init(exint_init_type *exint_struct) +{ + exint_struct->line_enable = FALSE; + exint_struct->line_select = EXINT_LINE_NONE; + exint_struct->line_polarity = EXINT_TRIGGER_FALLING_EDGE; + exint_struct->line_mode = EXINT_LINE_EVENT; +} + +/** + * @brief exint init + * @param exint_struct + * - to the structure of exint_init_type + * @retval none + */ +void exint_init(exint_init_type *exint_struct) +{ + uint32_t line_index = 0; + line_index = exint_struct->line_select; + + EXINT->inten &= ~line_index; + EXINT->evten &= ~line_index; + + if(exint_struct->line_enable != FALSE) + { + if(exint_struct->line_mode == EXINT_LINE_INTERRUPUT) + { + EXINT->inten |= line_index; + } + else + { + EXINT->evten |= line_index; + } + + EXINT->polcfg1 &= ~line_index; + EXINT->polcfg2 &= ~line_index; + if(exint_struct->line_polarity == EXINT_TRIGGER_RISING_EDGE) + { + EXINT->polcfg1 |= line_index; + } + else if(exint_struct->line_polarity == EXINT_TRIGGER_FALLING_EDGE) + { + EXINT->polcfg2 |= line_index; + } + else + { + EXINT->polcfg1 |= line_index; + EXINT->polcfg2 |= line_index; + } + } +} + +/** + * @brief clear exint flag + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval none + */ +void exint_flag_clear(uint32_t exint_line) +{ + EXINT->intsts = exint_line; +} + +/** + * @brief get exint flag + * @param exint_line + * this parameter can be one of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval the new state of exint flag(SET or RESET). + */ +flag_status exint_flag_get(uint32_t exint_line) +{ + flag_status status = RESET; + uint32_t exint_flag =0; + exint_flag = EXINT->intsts & exint_line; + if((exint_flag != (uint16_t)RESET)) + { + status = SET; + } + else + { + status = RESET; + } + return status; +} + +/** + * @brief generate exint software interrupt event + * @param exint_line + * this parameter can be one of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval none + */ +void exint_software_interrupt_event_generate(uint32_t exint_line) +{ + EXINT->swtrg |= exint_line; +} + +/** + * @brief enable or disable exint interrupt + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @param new_state: new state of exint interrupt. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void exint_interrupt_enable(uint32_t exint_line, confirm_state new_state) +{ + if(new_state == TRUE) + { + EXINT->inten |= exint_line; + } + else + { + EXINT->inten &= ~exint_line; + } +} + +/** + * @brief enable or disable exint event + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @param new_state: new state of exint event. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void exint_event_enable(uint32_t exint_line, confirm_state new_state) +{ + if(new_state == TRUE) + { + EXINT->evten |= exint_line; + } + else + { + EXINT->evten &= ~exint_line; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c new file mode 100644 index 0000000000..6aa059555d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c @@ -0,0 +1,1158 @@ +/** + ************************************************************************** + * @file at32f435_437_flash.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the flash firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +#ifdef FLASH_MODULE_ENABLED + +/** @defgroup FLASH_private_functions + * @{ + */ + +/** + * @brief check whether the specified flash flag is set or not. + * @param flash_flag: specifies the flash flag to check. + * this parameter can be one of flash flag status: + * - FLASH_OBF_FLAG + * - FLASH_ODF_FLAG + * - FLASH_PRGMERR_FLAG + * - FLASH_EPPERR_FLAG + * - FLASH_BANK1_OBF_FLAG + * - FLASH_BANK1_ODF_FLAG + * - FLASH_BANK1_PRGMERR_FLAG + * - FLASH_BANK1_EPPERR_FLAG + * - FLASH_BANK2_OBF_FLAG + * - FLASH_BANK2_ODF_FLAG + * - FLASH_BANK2_PRGMERR_FLAG + * - FLASH_BANK2_EPPERR_FLAG + * - FLASH_USDERR_FLAG + * @retval the new state of flash_flag (SET or RESET). + */ +flag_status flash_flag_get(uint32_t flash_flag) +{ + flag_status status = RESET; + uint32_t flag_position; + flag_position = flash_flag & 0x70000000; + flash_flag &= 0x8FFFFFFF; + switch(flag_position) + { + case 0x00000000: + if(FLASH->sts & flash_flag) + status = SET; + break; + case 0x10000000: + if(FLASH->sts2 & flash_flag) + status = SET; + break; + case 0x40000000: + if(FLASH->usd & flash_flag) + status = SET; + break; + default: + break; + } + /* return the new state of flash_flag (SET or RESET) */ + return status; +} + +/** + * @brief clear the flash flag. + * @param flash_flag: specifies the flash flags to clear. + * this parameter can be any combination of the following values: + * - FLASH_ODF_FLAG + * - FLASH_PRGMERR_FLAG + * - FLASH_EPPERR_FLAG + * - FLASH_BANK1_ODF_FLAG + * - FLASH_BANK1_PRGMERR_FLAG + * - FLASH_BANK1_EPPERR_FLAG + * - FLASH_BANK2_ODF_FLAG + * - FLASH_BANK2_PRGMERR_FLAG + * - FLASH_BANK2_EPPERR_FLAG + * @retval none + */ +void flash_flag_clear(uint32_t flash_flag) +{ + uint32_t flag_position; + flag_position = flash_flag & 0x70000000; + flash_flag &= 0x8FFFFFFF; + switch(flag_position) + { + case 0x00000000: + FLASH->sts = flash_flag; + break; + case 0x10000000: + FLASH->sts2 = flash_flag; + break; + default: + break; + } +} + +/** + * @brief return the flash operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief return the flash bank1 operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_bank1_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief return the flash bank2 operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_bank2_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts2_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts2_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts2_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief wait for flash operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the status */ + return status; +} + +/** + * @brief wait for flash bank1 operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank1_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_bank1_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_bank1_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the operation status */ + return status; +} + +/** + * @brief wait for flash bank2 operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank2_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_bank2_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_bank2_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the operation status */ + return status; +} + +/** + * @brief unlock the flash controller. + * @param none + * @retval none + */ +void flash_unlock(void) +{ + FLASH->unlock = FLASH_UNLOCK_KEY1; + FLASH->unlock = FLASH_UNLOCK_KEY2; + FLASH->unlock2 = FLASH_UNLOCK_KEY1; + FLASH->unlock2 = FLASH_UNLOCK_KEY2; +} + +/** + * @brief unlock the flash bank1 controller. + * @param none + * @retval none + */ +void flash_bank1_unlock(void) +{ + FLASH->unlock = FLASH_UNLOCK_KEY1; + FLASH->unlock = FLASH_UNLOCK_KEY2; +} + +/** + * @brief unlock the flash bank2 controller. + * @param none + * @retval none + */ +void flash_bank2_unlock(void) +{ + FLASH->unlock2 = FLASH_UNLOCK_KEY1; + FLASH->unlock2 = FLASH_UNLOCK_KEY2; +} + +/** + * @brief lock the flash controller. + * @param none + * @retval none + */ +void flash_lock(void) +{ + FLASH->ctrl_bit.oplk = TRUE; + FLASH->ctrl2_bit.oplk = TRUE; +} + +/** + * @brief lock the flash bank1 controller. + * @param none + * @retval none + */ +void flash_bank1_lock(void) +{ + FLASH->ctrl_bit.oplk = TRUE; +} + +/** + * @brief lock the flash bank2 controller. + * @param none + * @retval none + */ +void flash_bank2_lock(void) +{ + FLASH->ctrl2_bit.oplk = TRUE; +} + +/** + * @brief erase a specified flash sector. + * @param sector_address: the sector address to be erased. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_sector_erase(uint32_t sector_address) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((sector_address >= FLASH_BANK1_START_ADDR) && (sector_address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.secers = TRUE; + FLASH->addr = sector_address; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the secers bit */ + FLASH->ctrl_bit.secers = FALSE; + } + else if((sector_address >= FLASH_BANK2_START_ADDR) && (sector_address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.secers = TRUE; + FLASH->addr2 = sector_address; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the secers bit */ + FLASH->ctrl2_bit.secers = FALSE; + } + + /* return the erase status */ + return status; +} + +/** + * @brief erase a specified flash block. + * @param block_address: the block address to be erased. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_block_erase(uint32_t block_address) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((block_address >= FLASH_BANK1_START_ADDR) && (block_address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.blkers = TRUE; + FLASH->addr = block_address; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the blkers bit */ + FLASH->ctrl_bit.blkers = FALSE; + } + else if((block_address >= FLASH_BANK2_START_ADDR) && (block_address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.blkers = TRUE; + FLASH->addr2 = block_address; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the blkers bit */ + FLASH->ctrl2_bit.blkers = FALSE; + } + + /* return the erase status */ + return status; +} + +/** + * @brief erase flash all internal sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_internal_all_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl_bit.bankers = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl_bit.bankers = FALSE; + + if(status == FLASH_OPERATE_DONE) + { + /* if the previous operation is completed, continue to erase bank2 */ + FLASH->ctrl2_bit.bankers = TRUE; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl2_bit.bankers = FALSE; + } + /* return the erase status */ + return status; +} + +/** + * @brief erase flash bank1 sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank1_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl_bit.bankers = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl_bit.bankers = FALSE; + + /* return the erase status */ + return status; +} + +/** + * @brief erase flash bank2 sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank2_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl2_bit.bankers = TRUE; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl2_bit.bankers = FALSE; + + /* return the erase status */ + return status; +} + +/** + * @brief erase the flash user system data. + * @note this functions erase all user system data except the fap byte. + * the eopb0 byte value change to 0xFF, sram size maybe change too. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_user_system_data_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + uint16_t fap_val = FAP_RELIEVE_KEY; + /* get the flash access protection status */ + if(flash_fap_status_get() != RESET) + { + fap_val = 0x0000; + } + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* erase the user system data */ + FLASH->ctrl_bit.usders = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the usders bit */ + FLASH->ctrl_bit.usders = FALSE; + + if((status == FLASH_OPERATE_DONE) && (fap_val == FAP_RELIEVE_KEY)) + { + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the last flash access protection value */ + USD->fap = (uint16_t)fap_val; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /*disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + } + + /* return the status */ + return status; +} + +/** + * @brief config the extend sram byte eopb0 in user system data. + * @note the 256kb and below capacity mcu only support FLASH_EOPB0_SRAM_384K, + * FLASH_EOPB0_SRAM_448K or FLASH_EOPB0_SRAM_512K. + * @param data: the eopb0 value. + * this parameter can be one of the following values: + * - FLASH_EOPB0_SRAM_512K + * - FLASH_EOPB0_SRAM_448K + * - FLASH_EOPB0_SRAM_384K + * - FLASH_EOPB0_SRAM_320K + * - FLASH_EOPB0_SRAM_256K + * - FLASH_EOPB0_SRAM_192K + * - FLASH_EOPB0_SRAM_128K + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_eopb0_config(flash_usd_eopb0_type data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the default eopb0 value */ + USD->eopb0 = (uint16_t)data; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /*disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the status */ + return status; +} + +/** + * @brief program a word at a specified address. + * @param address: specifies the address to be programmed, word alignment is recommended. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_word_program(uint32_t address, uint32_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint32_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint32_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + + /* return the program status */ + return status; +} + +/** + * @brief program a halfword at a specified address. + * @param address: specifies the address to be programmed, halfword alignment is recommended. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_halfword_program(uint32_t address, uint16_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint16_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint16_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + + /* return the program status */ + return status; +} + +/** + * @brief program a byte at a specified address. + * @note this function cannot be used to program spim. + * @param address: specifies the address to be programmed. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_byte_program(uint32_t address, uint8_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint8_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint8_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + /* return the program status */ + return status; +} + +/** + * @brief program a halfword at a specified user system data address. + * @param address: specifies the address to be programmed. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_user_system_data_program(uint32_t address, uint8_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + if(address == USD_BASE) + { + if(data != 0xA5) + return FLASH_OPERATE_DONE; + } + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + *(__IO uint16_t*)address = data; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the user system data program status */ + return status; +} + +/** + * @brief config erase/program protection for the desired sectors. + * @param sector_bits: + * the pointer of the address of the sectors to be erase/program protected. + * general bit 0~31 every bit is used to protect the 4KB bytes, bit 62~32 + * every bit is used to protect the 128KB bytes + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_epp_set(uint32_t *sector_bits) +{ + uint16_t epp_data[4] = {0xFFFF,0xFFFF,0xFFFF,0xFFFF}; + flash_status_type status = FLASH_OPERATE_DONE; + sector_bits[0] = (uint32_t)(~sector_bits[0]); + epp_data[0] = (uint16_t)((sector_bits[0] >> 0) & 0xFF); + epp_data[1] = (uint16_t)((sector_bits[0] >> 8) & 0xFF); + epp_data[2] = (uint16_t)((sector_bits[0] >> 16) & 0xFF); + epp_data[3] = (uint16_t)((sector_bits[0] >> 24) & 0xFF); + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + FLASH->ctrl_bit.usdprgm = TRUE; + USD->epp0 = epp_data[0]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + if(status == FLASH_OPERATE_DONE) + { + USD->epp1 = epp_data[1]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp2 = epp_data[2]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp3 = epp_data[3]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + + sector_bits[1] = (uint32_t)(~sector_bits[1]); + epp_data[0] = (uint16_t)((sector_bits[1] >> 0) & 0xFF); + epp_data[1] = (uint16_t)((sector_bits[1] >> 8) & 0xFF); + epp_data[2] = (uint16_t)((sector_bits[1] >> 16) & 0xFF); + epp_data[3] = (uint16_t)((sector_bits[1] >> 24) & 0xFF); + if(status == FLASH_OPERATE_DONE) + { + USD->epp4 = epp_data[0]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp5 = epp_data[1]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp6 = epp_data[2]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp7 = epp_data[3]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the erase/program protection operation status */ + return status; +} + +/** + * @brief return the flash erase/program protection status. + * @param sector_bits: pointer to get the epps register. + * @retval none + */ +void flash_epp_status_get(uint32_t *sector_bits) +{ + /* return the flash erase/program protection register value */ + sector_bits[0] = (uint32_t)(FLASH->epps0); + sector_bits[1] = (uint32_t)(FLASH->epps1); +} + +/** + * @brief enable or disable the flash access protection. + * @note if the user has already programmed the other user system data before calling + * this function, must re-program them since this function erase all user system data. + * @param new_state: new state of the flash access protection. + * this parameter can be: TRUE or FALSE. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_fap_enable(confirm_state new_state) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + FLASH->ctrl_bit.usders = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + /* wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the usders bit */ + FLASH->ctrl_bit.usders = FALSE; + + if(status == FLASH_OPERATE_DONE) + { + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the default eopb0 value */ + USD->eopb0 = (uint16_t)0x0002; + + /* Wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + if(new_state == FALSE) + { + USD->fap = FAP_RELIEVE_KEY; + /* Wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + } + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + } + + /* return the flash access protection operation status */ + return status; +} + +/** + * @brief check the flash access protection status. + * @param none + * @retval flash access protection status(SET or RESET) + */ +flag_status flash_fap_status_get(void) +{ + return (flag_status)FLASH->usd_bit.fap; +} + +/** + * @brief program the flash system setting byte in usd: wdt_ato_en / depslp_rst / stdby_rst / btopt. + * @param usd_ssb: the system setting byte + * @note this parameter usd_ssb must contain a combination of all the following 6 types of data + * type 1: wdt_ato_en, select the wdt auto start + * this data can be one of the following values: + * - USD_WDT_ATO_DISABLE: disable wdt auto start + * - USD_WDT_ATO_ENABLE: enable wdt auto start + * type 2: depslp_rst, reset event when entering deepsleep mode. + * this data can be one of the following values: + * - USD_DEPSLP_NO_RST: no reset generated when entering in deepsleep + * - USD_DEPSLP_RST: reset generated when entering in deepsleep + * type 3: stdby_rst, reset event when entering standby mode. + * this data can be one of the following values: + * - USD_STDBY_NO_RST: no reset generated when entering in standby + * - USD_STDBY_RST: reset generated when entering in standby + * type 4: btopt, at startup,if boot pins are set in boot from user flash position,selected the device boot from bank1/bank2. + * this data can be one of the following values: + * - FLASH_BOOT_FROM_BANK1:boot from bank1 + * - FLASH_BOOT_FROM_BANK2:boot from bank 2 or bank 1 + * type 5: wdt_depslp, wdt stop/continue count when entering in deepsleep. + * this data can be one of the following values: + * - USD_WDT_DEPSLP_CONTINUE: wdt continue count + * - USD_WDT_DEPSLP_STOP: wdt stop count + * type 6: wdt_stdby, wdt stop/continue count when entering in standby. + * this data can be one of the following values: + * - USD_WDT_STDBY_CONTINUE: wdt continue count + * - USD_WDT_STDBY_STOP: wdt stop count + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_ssb_set(uint8_t usd_ssb) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + USD->ssb = usd_ssb; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the user system data program status */ + return status; +} + +/** + * @brief return the flash system setting byte status. + * @param none + * @retval values from flash_usd register: wdt_ato_en(bit0), depslp_rst(bit1), + * stdby_rst(bit2) and btopt(bit3). + */ +uint8_t flash_ssb_status_get(void) +{ + /* return the system setting byte status */ + return (uint8_t)(FLASH->usd >> 2); +} + +/** + * @brief enable or disable the specified flash interrupts. + * @param flash_int: specifies the flash interrupt sources to be enabled or disabled. + * this parameter can be any combination of the following values: + * - FLASH_ERR_INT + * - FLASH_ODF_INT + * - FLASH_BANK1_ERR_INT + * - FLASH_BANK1_ODF_INT + * - FLASH_BANK2_ERR_INT + * - FLASH_BANK2_ODF_INT + * @param new_state: new state of the specified flash interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_interrupt_enable(uint32_t flash_int, confirm_state new_state) +{ + if(flash_int & FLASH_BANK1_ERR_INT) + FLASH->ctrl_bit.errie = new_state; + if(flash_int & FLASH_BANK1_ODF_INT) + FLASH->ctrl_bit.odfie = new_state; + if(flash_int & FLASH_BANK2_ERR_INT) + FLASH->ctrl2_bit.errie = new_state; + if(flash_int & FLASH_BANK2_ODF_INT) + FLASH->ctrl2_bit.odfie = new_state; +} + +/** + * @brief enable security library function. + * @param pwd: slib password + * start_sector: security library start sector + * inst_start_sector: security library i-bus area start sector + * end_sector: security library end sector + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_slib_enable(uint32_t pwd, uint16_t start_sector, uint16_t inst_start_sector, uint16_t end_sector) +{ + uint32_t slib_range; + flash_status_type status = FLASH_OPERATE_DONE; + + /*check range param limits*/ + if((start_sector>=inst_start_sector) || ((inst_start_sector > end_sector) && \ + (inst_start_sector != 0xFFFF)) || (start_sector > end_sector)) + return FLASH_PROGRAM_ERROR; + + /* unlock slib cfg register */ + FLASH->slib_unlock = SLIB_UNLOCK_KEY; + while(FLASH->slib_misc_sts_bit.slib_ulkf==RESET); + + /* configure slib, set pwd and range */ + FLASH->slib_set_pwd = pwd; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + slib_range = ((uint32_t)(end_sector << 16) & FLASH_SLIB_END_SECTOR) | (start_sector & FLASH_SLIB_START_SECTOR); + FLASH->slib_set_range0 = slib_range; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + slib_range = (inst_start_sector & FLASH_SLIB_INST_START_SECTOR) | 0x80000000; + FLASH->slib_set_range1 = slib_range; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + } + + return status; +} + +/** + * @brief disable slib when slib enabled. + * @param pwd: slib password + * @retval success or error + */ +error_status flash_slib_disable(uint32_t pwd) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* write password to disable slib */ + FLASH->slib_pwd_clr = pwd; + + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + if(FLASH->slib_misc_sts_bit.slib_pwd_ok) + return SUCCESS; + else + return ERROR; + } + return ERROR; +} + +/** + * @brief get remaining count of slib(range: 256~0). + * @param none + * @retval uint32_t + */ +uint32_t flash_slib_remaining_count_get(void) +{ + return (uint32_t)FLASH->slib_misc_sts_bit.slib_rcnt; +} + +/** + * @brief get the slib state. + * @param none + * @retval SET or RESET + */ +flag_status flash_slib_state_get(void) +{ + if(FLASH->slib_sts0_bit.slib_enf) + return SET; + else + return RESET; +} + +/** + * @brief get the start sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_start_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts1_bit.slib_ss; +} + +/** + * @brief get the instruction start sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_inststart_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts2_bit.slib_inst_ss; +} + +/** + * @brief get the end sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_end_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts1_bit.slib_es; +} + +/** + * @brief flash crc calibration in main block. + * @param start_sector: crc calibration start sector number + * sector_cnt: crc calibration sector count + * @retval uint32: crc calibration result + */ +uint32_t flash_crc_calibrate(uint32_t start_sector, uint32_t sector_cnt) +{ + FLASH->crc_ctrl_bit.crc_ss = start_sector; + FLASH->crc_ctrl_bit.crc_sn = sector_cnt; + FLASH->crc_ctrl_bit.crc_strt = TRUE; + flash_operation_wait_for(OPERATION_TIMEOUT); + return FLASH->crc_chkr; +} + +/** + * @brief flash non-zero wait area boost enable. + * @param new_state: new state of the flash non-zero wait area boost operation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_nzw_boost_enable(confirm_state new_state) +{ + FLASH->psr_bit.nzw_bst = new_state; +} + +/** + * @brief flash continue read enable. + * @param new_state: new state of the flash continue read enable operation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_continue_read_enable(confirm_state new_state) +{ + FLASH->contr_bit.fcontr_en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c new file mode 100644 index 0000000000..cb62c5eb73 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c @@ -0,0 +1,523 @@ +/** + ************************************************************************** + * @file at32f435_437_gpio.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the gpio firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +#ifdef GPIO_MODULE_ENABLED + +/** @defgroup GPIO_private_functions + * @{ + */ + +/** + * @brief reset the gpio register + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval none + */ +void gpio_reset(gpio_type *gpio_x) +{ + if(gpio_x == GPIOA) + { + crm_periph_reset(CRM_GPIOA_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOA_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOB) + { + crm_periph_reset(CRM_GPIOB_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOB_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOC) + { + crm_periph_reset(CRM_GPIOC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOC_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOD) + { + crm_periph_reset(CRM_GPIOD_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOD_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOE) + { + crm_periph_reset(CRM_GPIOE_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOE_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOF) + { + crm_periph_reset(CRM_GPIOF_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOF_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOG) + { + crm_periph_reset(CRM_GPIOG_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOG_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOH) + { + crm_periph_reset(CRM_GPIOH_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOH_PERIPH_RESET, FALSE); + } +} + +/** + * @brief initialize the gpio peripheral. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param gpio_init_struct: pointer to gpio init structure. + * @retval none + */ +void gpio_init(gpio_type *gpio_x, gpio_init_type *gpio_init_struct) +{ + uint16_t pinx_value, pin_index = 0; + + pinx_value = (uint16_t)gpio_init_struct->gpio_pins; + + while(pinx_value > 0) + { + if(pinx_value & 0x01) + { + gpio_x->cfgr &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->cfgr |= (uint32_t)(gpio_init_struct->gpio_mode << (pin_index * 2)); + + gpio_x->omode &= (uint32_t)~(0x01 << (pin_index)); + gpio_x->omode |= (uint32_t)(gpio_init_struct->gpio_out_type << (pin_index)); + + gpio_x->odrvr &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->odrvr |= (uint32_t)(gpio_init_struct->gpio_drive_strength << (pin_index * 2)); + + gpio_x->pull &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->pull |= (uint32_t)(gpio_init_struct->gpio_pull << (pin_index * 2)); + } + pinx_value >>= 1; + pin_index++; + } +} + +/** + * @brief fill each gpio_init_type member with its default value. + * @param gpio_init_struct : pointer to a gpio_init_type structure which will be initialized. + * @retval none + */ +void gpio_default_para_init(gpio_init_type *gpio_init_struct) +{ + /* reset gpio init structure parameters values */ + gpio_init_struct->gpio_pins = GPIO_PINS_ALL; + gpio_init_struct->gpio_mode = GPIO_MODE_INPUT; + gpio_init_struct->gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct->gpio_pull = GPIO_PULL_NONE; + gpio_init_struct->gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; +} + +/** + * @brief read the specified input port pin. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be one of the following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * @retval flag_status (SET or RESET) + */ +flag_status gpio_input_data_bit_read(gpio_type *gpio_x, uint16_t pins) +{ + flag_status status = RESET; + + if(pins != (pins & gpio_x->idt)) + { + status = RESET; + } + else + { + status = SET; + } + + return status; +} + +/** + * @brief read the specified gpio input data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval gpio input data port value. + */ +uint16_t gpio_input_data_read(gpio_type *gpio_x) +{ + return ((uint16_t)(gpio_x->idt)); +} + +/** + * @brief read the specified output port pin. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be one of the following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * @retval flag_status (SET or RESET) + */ +flag_status gpio_output_data_bit_read(gpio_type *gpio_x, uint16_t pins) +{ + flag_status status = RESET; + + if((gpio_x->odt & pins) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief read the specified gpio ouput data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval gpio input data port value. + */ +uint16_t gpio_output_data_read(gpio_type *gpio_x) +{ + return ((uint16_t)(gpio_x->odt)); +} + +/** + * @brief set the selected data port bits. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_bits_set(gpio_type *gpio_x, uint16_t pins) +{ + gpio_x->scr = pins; +} + +/** + * @brief clear the selected data port bits. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_bits_reset(gpio_type *gpio_x, uint16_t pins) +{ + gpio_x->clr = pins; +} + +/** + * @brief set or clear the selected data port bit. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @param bit_state: specifies the value to be written to the selected bit (TRUE or FALSE). + * @retval none + */ +void gpio_bits_write(gpio_type *gpio_x, uint16_t pins, confirm_state bit_state) +{ + if(bit_state != FALSE) + { + gpio_x->scr = pins; + } + else + { + gpio_x->clr = pins; + } +} + +/** + * @brief write data to the specified gpio data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param port_value: specifies the value to be written to the port output data register. + * @retval none + */ +void gpio_port_write(gpio_type *gpio_x, uint16_t port_value) +{ + gpio_x->odt = port_value; +} + +/** + * @brief write protect gpio pins configuration registers. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be any combination of the following: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_pin_wp_config(gpio_type *gpio_x, uint16_t pins) +{ + uint32_t temp = 0x00010000; + + temp |= pins; + /* set wpen bit */ + gpio_x->wpr = temp; + /* reset wpen bit */ + gpio_x->wpr = pins; + /* set wpen bit */ + gpio_x->wpr = temp; + /* read wpen bit*/ + temp = gpio_x->wpr; + /* read wpen bit*/ + temp = gpio_x->wpr; +} + +/** + * @brief enable or disable gpio pins huge driven. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @param new_state: new state of the slew rate. + * this parameter can be: true or false. + * @retval none + */ +void gpio_pins_huge_driven_config(gpio_type *gpio_x, uint16_t pins, confirm_state new_state) +{ + if(new_state != FALSE) + { + gpio_x->hdrv |= pins; + } + else + { + gpio_x->hdrv &= ~pins; + } +} + +/** + * @brief configure the pin's muxing function. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param gpio_pin_source: specifies the pin for the muxing function. + * this parameter can be one of the following values: + * - GPIO_PINS_SOURCE0 + * - GPIO_PINS_SOURCE1 + * - GPIO_PINS_SOURCE2 + * - GPIO_PINS_SOURCE3 + * - GPIO_PINS_SOURCE4 + * - GPIO_PINS_SOURCE5 + * - GPIO_PINS_SOURCE6 + * - GPIO_PINS_SOURCE7 + * - GPIO_PINS_SOURCE8 + * - GPIO_PINS_SOURCE9 + * - GPIO_PINS_SOURCE10 + * - GPIO_PINS_SOURCE11 + * - GPIO_PINS_SOURCE12 + * - GPIO_PINS_SOURCE13 + * - GPIO_PINS_SOURCE14 + * - GPIO_PINS_SOURCE15 + * @param gpio_mux: select the pin to used as muxing function. + * this parameter can be one of the following values: + * - GPIO_MUX_0 + * - GPIO_MUX_1 + * - GPIO_MUX_2 + * - GPIO_MUX_3 + * - GPIO_MUX_4 + * - GPIO_MUX_5 + * - GPIO_MUX_6 + * - GPIO_MUX_7 + * - GPIO_MUX_8 + * - GPIO_MUX_9 + * - GPIO_MUX_10 + * - GPIO_MUX_11 + * - GPIO_MUX_12 + * - GPIO_MUX_13 + * - GPIO_MUX_14 + * - GPIO_MUX_15 + * @retval none + */ +void gpio_pin_mux_config(gpio_type *gpio_x, gpio_pins_source_type gpio_pin_source, gpio_mux_sel_type gpio_mux) +{ + uint32_t temp = 0x00; + uint32_t temp_2 = 0x00; + + temp = ((uint32_t)(gpio_mux) << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + if(gpio_pin_source >> 0x03) + { + gpio_x->muxh &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + temp_2 = gpio_x->muxh | temp; + gpio_x->muxh = temp_2; + } + else + { + gpio_x->muxl &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + temp_2 = gpio_x->muxl | temp; + gpio_x->muxl = temp_2; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c new file mode 100644 index 0000000000..d91f033ce6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c @@ -0,0 +1,748 @@ +/** + ************************************************************************** + * @file at32f435_437_i2c.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the i2c firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +#ifdef I2C_MODULE_ENABLED + +/** @defgroup I2C_private_functions + * @{ + */ + +/** + * @brief reset the i2c register + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_reset(i2c_type *i2c_x) +{ + if(i2c_x == I2C1) + { + crm_periph_reset(CRM_I2C1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C1_PERIPH_RESET, FALSE); + } + else if(i2c_x == I2C2) + { + crm_periph_reset(CRM_I2C2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C2_PERIPH_RESET, FALSE); + } + else if(i2c_x == I2C3) + { + crm_periph_reset(CRM_I2C3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C3_PERIPH_RESET, FALSE); + } +} + +/** + * @brief init i2c digit filters and clock control register. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param dfilters: number of digit filters (0x00~0x0F). + * @param clk: i2c clock control register (0x00000000~0xFFFFFFFF). + * @retval none + */ +void i2c_init(i2c_type *i2c_x, uint8_t dfilters, uint32_t clk) +{ + /* disable i2c peripheral */ + i2c_x->ctrl1_bit.i2cen = FALSE; + + /* write clkctrl register*/ + i2c_x->clkctrl = clk; + + /* write digital filter register*/ + i2c_x->ctrl1_bit.dflt = dfilters; +} + +/** + * @brief config i2c own address 1. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param mode: i2c address mode. + * this parameter can be one of the following values: + * - I2C_ADDRESS_MODE_7BIT: 7bit address. + * - I2C_ADDRESS_MODE_10BIT: 10bit address. + * @param address: own address 1, such as 0xB0. + * @retval none + */ +void i2c_own_address1_set(i2c_type *i2c_x, i2c_address_mode_type mode, uint16_t address) +{ + /* config address mode */ + i2c_x->oaddr1_bit.addr1mode = mode; + + /* config address */ + i2c_x->oaddr1_bit.addr1 = address & 0x03FF; + + /* enable address */ + i2c_x->oaddr1_bit.addr1en = TRUE; +} + +/** + * @brief config i2c own address 2 and mask. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: own address 1, such as 0xC0. + * @param mask: own address 2 mask. + * this parameter can be one of the following values: + * - I2C_ADDR2_NOMASK: compare bit [7:1]. + * - I2C_ADDR2_MASK01: only compare bit [7:2]. + * - I2C_ADDR2_MASK02: only compare bit [7:2]. + * - I2C_ADDR2_MASK03: only compare bit [7:3]. + * - I2C_ADDR2_MASK04: only compare bit [7:4]. + * - I2C_ADDR2_MASK05: only compare bit [7:5]. + * - I2C_ADDR2_MASK06: only compare bit [7:6]. + * - I2C_ADDR2_MASK07: only compare bit [7]. + * @retval none + */ +void i2c_own_address2_set(i2c_type *i2c_x, uint8_t address, i2c_addr2_mask_type mask) +{ + i2c_x->oaddr2_bit.addr2mask = mask; + + i2c_x->oaddr2_bit.addr2 = (address >> 1) & 0x7F; +} + +/** + * @brief enable or disable own address 2. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_own_address2_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->oaddr2_bit.addr2en = new_state; +} + +/** + * @brief enable or disable smbus mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param mode: smbus device mode. + * this parameter can be one of the following values: + * - I2C_SMBUS_MODE_DEVICE: smbus device. + * - I2C_SMBUS_MODE_HOST: smbus host. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_smbus_enable(i2c_type *i2c_x, i2c_smbus_mode_type mode, confirm_state new_state) +{ + switch (mode) + { + case I2C_SMBUS_MODE_DEVICE: + i2c_x->ctrl1_bit.devaddren = new_state; + break; + case I2C_SMBUS_MODE_HOST: + i2c_x->ctrl1_bit.haddren = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable peripheral. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.i2cen = new_state; +} + +/** + * @brief enable or disable clock stretch. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_clock_stretch_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.stretch = (!new_state); +} + +/** + * @brief enable or disable ack. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void i2c_ack_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.nacken = (!new_state); +} + +/** + * @brief enable or disable 10-bit address mode (master transfer). + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_addr10_mode_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.addr10 = new_state; +} + +/** + * @brief config the slave address to be transmitted. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: slave address. + * @retval none + */ +void i2c_transfer_addr_set(i2c_type *i2c_x, uint16_t address) +{ + i2c_x->ctrl2_bit.saddr = address & 0x03FF; +} + +/** + * @brief get the slave address to be transmitted. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval slave address + */ +uint16_t i2c_transfer_addr_get(i2c_type *i2c_x) +{ + return i2c_x->ctrl2_bit.saddr; +} + +/** + * @brief config the master transfer direction. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param i2c_direction: transfer request direction. + * this parameter can be one of the following values: + * - I2C_DIR_TRANSMIT: master request a write transfer. + * - I2C_DIR_RECEIVE: master request a read transfer. + * @retval none + */ +void i2c_transfer_dir_set(i2c_type *i2c_x, i2c_transfer_dir_type i2c_direction) +{ + i2c_x->ctrl2_bit.dir = i2c_direction; +} + +/** + * @brief slave get the i2c transfer direction. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the slave direction + * - I2C_DIR_TRANSMIT: master request a write transfer, slave enters receiver mode. + * - I2C_DIR_RECEIVE: master request a read transfer, slave enters transmitter mode. + */ +i2c_transfer_dir_type i2c_transfer_dir_get(i2c_type *i2c_x) +{ + if (i2c_x->sts_bit.sdir == 0) + { + return I2C_DIR_TRANSMIT; + } + else + { + return I2C_DIR_RECEIVE; + } +} + +/** + * @brief get the i2c slave matched address. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval slave matched address. + */ +uint8_t i2c_matched_addr_get(i2c_type *i2c_x) +{ + return (i2c_x->sts_bit.addr << 1); +} + +/** + * @brief enable or disable auto send stop mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_auto_stop_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.astopen = new_state; +} + +/** + * @brief enable or disable cnt reload mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_reload_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.rlden = new_state; +} + +/** + * @brief config the transfer cnt . + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param cnt: transfer cnt. + * @retval none + */ +void i2c_cnt_set(i2c_type *i2c_x, uint8_t cnt) +{ + i2c_x->ctrl2_bit.cnt = cnt; +} + +/** + * @brief enable or disable read 10-bit header, this mode + * only used in 10-bit address mode read. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_addr10_header_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.readh10 = new_state; +} + +/** + * @brief enable or disable general call mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_general_call_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.gcaen = new_state; +} + +/** + * @brief drives the smbus alert pin high or low. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param level + * this parameter can be one of the following values: + * - I2C_SMBUS_ALERT_LOW: smbus alert set low. + * - I2C_SMBUS_ALERT_HIGH: smbus alert set high. + * @retval none + */ +void i2c_smbus_alert_set(i2c_type *i2c_x, i2c_smbus_alert_set_type level) +{ + i2c_x->ctrl1_bit.smbalert = level; +} + +/** + * @brief enable or disable slave data control. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_slave_data_ctrl_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.sctrl = new_state; +} + +/** + * @brief enable or disable pec calculate. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_pec_calculate_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.pecen = new_state; +} + +/** + * @brief enable or disable pec transfer. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_pec_transmit_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.pecten = new_state; +} + +/** + * @brief get the i2c pec value. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the pec. + */ +uint8_t i2c_pec_value_get(i2c_type *i2c_x) +{ + return (uint8_t)(i2c_x->pec_bit.pecval); +} + +/** + * @brief config the i2c bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param timeout: timeout (0x0000~0x0FFF). + * @retval none + */ +void i2c_timeout_set(i2c_type *i2c_x, uint16_t timeout) +{ + i2c_x->timeout_bit.totime = timeout; +} + +/** + * @brief config the bus timeout detcet level. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param level + * this parameter can be one of the following values: + * - I2C_TIMEOUT_DETCET_HIGH: detect high level timeout. + * - I2C_TIMEOUT_DETCET_LOW: detect low level timeout. + * @retval none + */ +void i2c_timeout_detcet_set(i2c_type *i2c_x, i2c_timeout_detcet_type mode) +{ + i2c_x->timeout_bit.tomode = mode; +} + +/** + * @brief enable or disable bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_timeout_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->timeout_bit.toen = new_state; +} + +/** + * @brief config the i2c extend bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param timeout: extend timeout (0x0000~0x0FFF). + * @retval none + */ +void i2c_ext_timeout_set(i2c_type *i2c_x, uint16_t timeout) +{ + i2c_x->timeout_bit.exttime = timeout; +} + +/** + * @brief enable or disable extend bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_ext_timeout_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->timeout_bit.exten = new_state; +} + +/** + * @brief enable or disable interrupts. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param i2c_int: interrupts sources. + * this parameter can be one of the following values: + * - I2C_TD_INT: transmit data interrupt. + * - I2C_RD_INT: receive data interrupt. + * - I2C_ADDR_INT: address match interrupt. + * - I2C_ACKFIAL_INT: ack fail interrupt. + * - I2C_STOP_INT: stop detect interrupt. + * - I2C_TDC_INT: transmit data complete interrupt. + * - I2C_ERR_INT: bus error interrupt. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_interrupt_enable(i2c_type *i2c_x, uint32_t source, confirm_state new_state) +{ + if (new_state != FALSE) + { + i2c_x->ctrl1 |= source; + } + else + { + i2c_x->ctrl1 &= (uint32_t)~source; + } +} + +/** + * @brief get interrupt status + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param source + * this parameter can be one of the following values: + * - I2C_TD_INT: transmit data interrupt. + * - I2C_RD_INT: receive data interrupt. + * - I2C_ADDR_INT: address match interrupt. + * - I2C_ACKFIAL_INT: ack fail interrupt. + * - I2C_STOP_INT: stop detect interrupt. + * - I2C_TDC_INT: transmit data complete interrupt. + * - I2C_ERR_INT: bus error interrupt. + * @retval flag_status (SET or RESET) + */ +flag_status i2c_interrupt_get(i2c_type *i2c_x, uint16_t source) +{ + if((i2c_x->ctrl1 & source) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable dma requests. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param dma_req: dma transfer request. + * this parameter can be one of the following values: + * - I2C_DMA_REQUEST_TX: dma transmit request. + * - I2C_DMA_REQUEST_RX: dma receive request. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_dma_enable(i2c_type *i2c_x, i2c_dma_request_type dma_req, confirm_state new_state) +{ + if(dma_req == I2C_DMA_REQUEST_TX) + { + i2c_x->ctrl1_bit.dmaten = new_state; + } + else + { + i2c_x->ctrl1_bit.dmaren = new_state; + } +} + +/** + * @brief config data transfer. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: slave address. + * @param cnt: transfer conuter(0~255) + * @param rld_stop: config reload and gen stop condition mode. + * this parameter can be one of the following values: + * - I2C_AUTO_STOP_MODE: auto generate stop mode. + * - I2C_SOFT_STOP_MODE: soft generate stop mode. + * - I2C_RELOAD_MODE: reload mode. + * @param start: config gen start condition mode. + * this parameter can be one of the following values: + * - I2C_WITHOUT_START: transfer data without start condition. + * - I2C_GEN_START_READ: read data and generate start. + * - I2C_GEN_START_WRITE: send data and generate start. + * @retval none + */ +void i2c_transmit_set(i2c_type *i2c_x, uint16_t address, uint8_t cnt, i2c_reload_stop_mode_type rld_stop, i2c_start_mode_type start) +{ + uint32_t temp; + + /* copy ctrl2 value to temp */ + temp = i2c_x->ctrl2; + + /* clear ctrl2_bit specific bits */ + temp &= ~0x03FF67FF; + + /* transfer mode and address set */ + temp |= address | rld_stop | start; + + /* transfer counter set */ + temp |= (uint32_t)cnt << 16; + + /* update ctrl2 value */ + i2c_x->ctrl2 = temp; +} + +/** + * @brief generate start condition. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_start_generate(i2c_type *i2c_x) +{ + i2c_x->ctrl2_bit.genstart = TRUE; +} + +/** + * @brief generate stop condition. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_stop_generate(i2c_type *i2c_x) +{ + i2c_x->ctrl2_bit.genstop = TRUE; +} + +/** + * @brief send a byte through the i2c periph. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param data: byte to be transmitted. + * @retval none + */ +void i2c_data_send(i2c_type *i2c_x, uint8_t data) +{ + i2c_x->txdt = data; +} + +/** + * @brief receive a byte through the i2c periph. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the received data. + */ +uint8_t i2c_data_receive(i2c_type *i2c_x) +{ + return (uint8_t)i2c_x->rxdt; +} + +/** + * @brief get flag status. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - I2C_TDBE_FLAG: transmit data buffer empty flag. + * - I2C_TDIS_FLAG: send interrupt status. + * - I2C_RDBF_FLAG: receive data buffer full flag. + * - I2C_ADDRF_FLAG: 0~7 bit address match flag. + * - I2C_ACKFAIL_FLAG: acknowledge failure flag. + * - I2C_STOPF_FLAG: stop condition generation complete flag. + * - I2C_TDC_FLAG: transmit data complete flag. + * - I2C_TCRLD_FLAG: transmission is complete, waiting to load data. + * - I2C_BUSERR_FLAG: bus error flag. + * - I2C_ARLOST_FLAG: arbitration lost flag. + * - I2C_OUF_FLAG: overflow or underflow flag. + * - I2C_PECERR_FLAG: pec receive error flag. + * - I2C_TMOUT_FLAG: smbus timeout flag. + * - I2C_ALERTF_FLAG: smbus alert flag. + * - I2C_BUSYF_FLAG: bus busy flag transmission mode. + * - I2C_SDIR_FLAG: slave data transmit direction. + * @retval the new state of flag (SET or RESET). + */ +flag_status i2c_flag_get(i2c_type *i2c_x, uint32_t flag) +{ + if((i2c_x->sts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear flag status + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - I2C_ADDRF_FLAG: 0~7 bit address match flag. + * - I2C_ACKFAIL_FLAG: acknowledge failure flag. + * - I2C_STOPF_FLAG: stop condition generation complete flag. + * - I2C_BUSERR_FLAG: bus error flag. + * - I2C_ARLOST_FLAG: arbitration lost flag. + * - I2C_OUF_FLAG: overflow or underflow flag. + * - I2C_PECERR_FLAG: pec receive error flag. + * - I2C_TMOUT_FLAG: smbus timeout flag. + * - I2C_ALERTF_FLAG: smbus alert flag. + * @retval none + */ +void i2c_flag_clear(i2c_type *i2c_x, uint32_t flag) +{ + i2c_x->clr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c new file mode 100644 index 0000000000..9fa3ab1110 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c @@ -0,0 +1,173 @@ +/** + ************************************************************************** + * @file at32f435_437_misc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the misc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +#ifdef MISC_MODULE_ENABLED + +/** @defgroup MISC_private_functions + * @{ + */ + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +/** + * @brief system reset + * @param none + * @retval none + */ +void nvic_system_reset(void) +{ + NVIC_SystemReset(); +} + +/** + * @brief enable nvic irq + * @param irqn (IRQn_Type number) + * @param preempt_priority: preemptive priority value (starting from 0) + * @param sub_priority: subpriority value (starting from 0) + * @retval none + */ +void nvic_irq_enable(IRQn_Type irqn, uint32_t preempt_priority, uint32_t sub_priority) +{ + uint32_t temp_priority = 0; + + /* encode priority */ + temp_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preempt_priority, sub_priority); + /* set priority */ + NVIC_SetPriority(irqn, temp_priority); + /* enable irqn */ + NVIC_EnableIRQ(irqn); +} + +/** + * @brief disable nvic irq number + * @param irqn (IRQn_Type number) + * @retval none + */ +void nvic_irq_disable(IRQn_Type irqn) +{ + NVIC_DisableIRQ(irqn); +} + +/** + * @brief config nvic priority group + * @param priority_group + * this parameter can be one of the following values: + * - NVIC_PRIORITY_GROUP_0 + * - NVIC_PRIORITY_GROUP_1 + * - NVIC_PRIORITY_GROUP_2 + * - NVIC_PRIORITY_GROUP_3 + * - NVIC_PRIORITY_GROUP_4 + * @retval none + */ +void nvic_priority_group_config(nvic_priority_group_type priority_group) +{ + /* set the prigroup[10:8] bits according to nvic_prioritygroup value */ + NVIC_SetPriorityGrouping(priority_group); +} + +/** + * @brief set the vector table location and offset. + * @param base + * this parameter can be one of the following values: + * - NVIC_VECTTAB_RAM + * - NVIC_VECTTAB_FLASH + * @param offset (vector table base offset field. this value must be a multiple of 0x200) + * @retval none + */ +void nvic_vector_table_set(uint32_t base, uint32_t offset) +{ + SCB->VTOR = base | (offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief config nvic lowpower mode + * @param lp_mode + * this parameter can be one of the following values: + * - NVIC_LP_SEVONPEND + * - NVIC_LP_SLEEPDEEP + * - NVIC_LP_SLEEPONEXIT + * @param new_state (new state of lp condition. ENABLE or DISABLE) + * @retval none + */ +void nvic_lowpower_mode_config(nvic_lowpower_mode_type lp_mode, confirm_state new_state) +{ + if(new_state != FALSE) + { + SCB->SCR |= lp_mode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)lp_mode); + } +} + +/** + * @brief config systick clock source + * @param source + * this parameter can be one of the following values: + * - SYSTICK_CLOCK_SOURCE_AHBCLK_DIV8 + * - SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV + * @retval none + */ +void systick_clock_source_config(systick_clock_source_type source) +{ + if(source == SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV) + { + SysTick->CTRL |= SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV; + } + else + { + SysTick->CTRL &= ~(uint32_t)SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c new file mode 100644 index 0000000000..b952928ff8 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c @@ -0,0 +1,250 @@ +/** + ************************************************************************** + * @file at32f435_437_pwc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the pwc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup PWC + * @brief PWC driver modules + * @{ + */ + +#ifdef PWC_MODULE_ENABLED + +/** @defgroup PWC_private_functions + * @{ + */ + +/** + * @brief deinitialize the pwc peripheral registers to their default reset values. + * @param none + * @retval none + */ +void pwc_reset(void) +{ + crm_periph_reset(CRM_PWC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_PWC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable access to the battery powered domain. + * @param new_state: new state of battery powered domain access. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void pwc_battery_powered_domain_access(confirm_state new_state) +{ + PWC->ctrl_bit.bpwen= new_state; +} + +/** + * @brief select the voltage threshold detected by the power voltage detector. + * @param pvm_voltage: select pwc pvm voltage + * this parameter can be one of the following values: + * - PWC_PVM_VOLTAGE_2V3 + * - PWC_PVM_VOLTAGE_2V4 + * - PWC_PVM_VOLTAGE_2V5 + * - PWC_PVM_VOLTAGE_2V6 + * - PWC_PVM_VOLTAGE_2V7 + * - PWC_PVM_VOLTAGE_2V8 + * - PWC_PVM_VOLTAGE_2V9 + * @retval none + */ +void pwc_pvm_level_select(pwc_pvm_voltage_type pvm_voltage) +{ + PWC->ctrl_bit.pvmsel= pvm_voltage; +} + +/** + * @brief enable or disable pwc power voltage monitor (pvm) + * @param new_state: new state of pvm. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void pwc_power_voltage_monitor_enable(confirm_state new_state) +{ + PWC->ctrl_bit.pvmen= new_state; +} + +/** + * @brief enable or disable pwc standby wakeup pin + * @param pin_num: choose the wakeup pin. + * this parameter can be be any combination of the following values: + * - PWC_WAKEUP_PIN_1 + * - PWC_WAKEUP_PIN_2 + * @param new_state: new state of the standby wakeup pin. + * this parameter can be one of the following values: + * - TRUE + * - FALSE + * @retval none + */ +void pwc_wakeup_pin_enable(uint32_t pin_num, confirm_state new_state) +{ + if(new_state == TRUE) + { + PWC->ctrlsts |= pin_num; + } + else + { + PWC->ctrlsts &= ~pin_num; + } +} + +/** + * @brief clear flag of pwc + * @param pwc_flag: select the pwc flag. + * this parameter can be any combination of the following values: + * - PWC_WAKEUP_FLAG + * - PWC_STANDBY_FLAG + * - note:"PWC_PVM_OUTPUT_FLAG" cannot be choose!this bit is readonly bit,it means the voltage monitoring output state + * @retval none + */ +void pwc_flag_clear(uint32_t pwc_flag) +{ + if(pwc_flag & PWC_STANDBY_FLAG) + PWC->ctrl_bit.clsef = TRUE; + if(pwc_flag & PWC_WAKEUP_FLAG) + PWC->ctrl_bit.clswef = TRUE; +} + +/** + * @brief get flag of pwc + * @param pwc_flag: select the pwc flag. + * this parameter can be one of the following values: + * - PWC_WAKEUP_FLAG + * - PWC_STANDBY_FLAG + * - PWC_PVM_OUTPUT_FLAG + * @retval state of select flag(SET or RESET). + */ +flag_status pwc_flag_get(uint32_t pwc_flag) +{ + flag_status status = RESET; + if ((PWC->ctrlsts & pwc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief enter pwc sleep mode + * @param sleep_mode_enter: choose the instruction to enter sleep mode. + * this parameter can be one of the following values: + * - PWC_SLEEP_ENTER_WFI + * - PWC_SLEEP_ENTER_WFE + * @retval none + */ +void pwc_sleep_mode_enter(pwc_sleep_enter_type pwc_sleep_enter) +{ + SCB->SCR &= (uint32_t)~0x4; + if(pwc_sleep_enter == PWC_SLEEP_ENTER_WFE) + { + __SEV(); + __WFE(); + __WFE(); + } + else if(pwc_sleep_enter == PWC_SLEEP_ENTER_WFI) + { + __WFI(); + } +} + +/** + * @brief enter pwc deep-sleep mode + * @param pwc_deep_sleep_enter: choose the instruction to enter deep sleep mode. + * this parameter can be one of the following values: + * - PWC_DEEP_SLEEP_ENTER_WFI + * - PWC_DEEP_SLEEP_ENTER_WFE + * @retval none + */ +void pwc_deep_sleep_mode_enter(pwc_deep_sleep_enter_type pwc_deep_sleep_enter) +{ + SCB->SCR |= 0x04; + if(pwc_deep_sleep_enter == PWC_DEEP_SLEEP_ENTER_WFE) + { + __SEV(); + __WFE(); + __WFE(); + } + else if(pwc_deep_sleep_enter == PWC_DEEP_SLEEP_ENTER_WFI) + { + __WFI(); + } + SCB->SCR &= (uint32_t)~0x4; +} + +/** + * @brief regulate low power consumption in the deep sleep mode + * @param pwc_regulator: set the regulator state. + * this parameter can be one of the following values: + * - PWC_REGULATOR_ON + * - PWC_REGULATOR_LOW_POWER + * @retval none + */ +void pwc_voltage_regulate_set(pwc_regulator_type pwc_regulator) +{ + PWC->ctrl_bit.vrsel = pwc_regulator; +} + +/** + * @brief enter pwc standby mode + * @param none + * @retval none + */ +void pwc_standby_mode_enter(void) +{ + PWC->ctrl_bit.clswef = TRUE; + PWC->ctrl_bit.lpsel = TRUE; + SCB->SCR |= 0x04; +#if defined (__CC_ARM) + __force_stores(); +#endif + while(1) + { + __WFI(); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c new file mode 100644 index 0000000000..04facef797 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c @@ -0,0 +1,430 @@ +/** + ************************************************************************** + * @file at32f435_437_qspi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contain all the functions for qspi firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup QSPI + * @brief QSPI driver modules + * @{ + */ + +#ifdef QSPI_MODULE_ENABLED + +/** @defgroup QSPI_private_functions + * @{ + */ + +/** + * @brief enable/disable encryption for qspi. + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_encryption_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl_bit.keyen = new_state; +} + +/** + * @brief set qspi sck mode. + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_mode: new state to be set + * this parameter can be one of the following values: + * - QSPI_SCK_MODE_0 + * - QSPI_SCK_MODE_3 + * @retval none + */ +void qspi_sck_mode_set(qspi_type* qspi_x, qspi_clk_mode_type new_mode) +{ + qspi_x->ctrl_bit.sckmode = new_mode; +} + +/** + * @brief set qspi clock division + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_clkdiv: new division value + * this parameter can be one of the following values: + * - QSPI_CLK_DIV_2 + * - QSPI_CLK_DIV_4 + * - QSPI_CLK_DIV_6 + * - QSPI_CLK_DIV_8 + * - QSPI_CLK_DIV_3 + * - QSPI_CLK_DIV_5 + * - QSPI_CLK_DIV_10 + * - QSPI_CLK_DIV_12 + * @retval none + */ +void qspi_clk_division_set(qspi_type* qspi_x, qspi_clk_div_type new_clkdiv) +{ + qspi_x->ctrl_bit.clkdiv = new_clkdiv; +} + +/** + * @brief enable/disable cache in xip mode + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_xip_cache_bypass_set(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->xip_cmd_w3_bit.bypassc = new_state; +} + +/** + * @brief enable/disable interrupt when command is completed + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_interrupt_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl2_bit.cmdie = new_state; +} + +/** + * @brief get status flags. + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - QSPI_RXFIFORDY_FLAG + * - QSPI_TXFIFORDY_FLAG + * - QSPI_CMDSTS_FLAG + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag) +{ + flag_status bit_status = RESET; + switch(flag) + { + case QSPI_RXFIFORDY_FLAG: + bit_status = (flag_status)qspi_x->fifosts_bit.rxfifordy; + break; + case QSPI_TXFIFORDY_FLAG: + bit_status = (flag_status)qspi_x->fifosts_bit.txfifordy; + break; + case QSPI_CMDSTS_FLAG: + bit_status = (flag_status)qspi_x->cmdsts_bit.cmdsts; + break; + default: + break; + } + return bit_status; +} + +/** + * @brief clear flags + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param flag: flags to be clear + * this parameter can be one of the following values: + * - QSPI_CMDSTS_FLAG + * @retval none + */ +void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag) +{ + UNUSED(flag); + qspi_x->cmdsts = QSPI_CMDSTS_FLAG; +} + +/** + * @brief set dma threshold for dma rx + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_threshold: value to set + * this parameter can be one of the following values: + * - QSPI_DMA_FIFO_THOD_WORD08 + * - QSPI_DMA_FIFO_THOD_WORD16 + * - QSPI_DMA_FIFO_THOD_WORD32 + * @retval none + */ +void qspi_dma_rx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold) +{ + qspi_x->ctrl2_bit.rxfifo_thod = new_threshold; +} + +/** + * @brief set dma threshold for dma tx + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_threshold: value to set + * this parameter can be one of the following values: + * - QSPI_DMA_FIFO_THOD_WORD08 + * - QSPI_DMA_FIFO_THOD_WORD16 + * - QSPI_DMA_FIFO_THOD_WORD32 + * @retval none + */ +void qspi_dma_tx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold) +{ + qspi_x->ctrl2_bit.txfifo_thod = new_threshold; +} + +/** + * @brief enable/disable dma transfer + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_dma_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl2_bit.dmaen = new_state; +} + +/** + * @brief set wip position in status register of flash + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param busy_pos: value to set + * this parameter can be one of the following values: + * - QSPI_BUSY_OFFSET_0 + * - QSPI_BUSY_OFFSET_1 + * - QSPI_BUSY_OFFSET_2 + * - QSPI_BUSY_OFFSET_3 + * - QSPI_BUSY_OFFSET_4 + * - QSPI_BUSY_OFFSET_5 + * - QSPI_BUSY_OFFSET_6 + * - QSPI_BUSY_OFFSET_7 + * @retval none + */ +void qspi_busy_config(qspi_type* qspi_x, qspi_busy_pos_type busy_pos) +{ + qspi_x->ctrl_bit.busy = busy_pos; +} + +/** + * @brief enable xip mode or command-port mode. + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_xip_enable(qspi_type* qspi_x, confirm_state new_state) +{ + /* skip if state is no change */ + if(new_state == (confirm_state)(qspi_x->ctrl_bit.xipsel)) + { + return; + } + + /* wait until tx fifo emoty*/ + while(qspi_x->fifosts_bit.txfifordy == 0); + + /* flush and reset qspi state */ + qspi_x->ctrl_bit.xiprcmdf = 1; + + /* wait until action is finished */ + while(qspi_x->ctrl_bit.abort); + + /* set xip mode to new state */ + qspi_x->ctrl_bit.xipsel = new_state; + + /* wait until abort is not set */ + while(qspi_x->ctrl_bit.abort); + + /* wait until cache status valid*/ + if(new_state == TRUE) + { + while( qspi_x->xip_cmd_w3_bit.csts ); + } +} + +/** + * @brief set command-port and qspi_x will start to work + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param qspi_cmd_struct: pointer to qspi cmd structure + * @retval none + */ +void qspi_cmd_operation_kick(qspi_type* qspi_x, qspi_cmd_type* qspi_cmd_struct) +{ + uint32_t w1_val = 0, w3_val = 0; + + /* config analyse cmd_w0 register */ + qspi_x->cmd_w0 = (uint32_t)qspi_cmd_struct->address_code; + + /* config analyse cmd_w1 register */ + w1_val = (uint32_t)qspi_cmd_struct->address_length; + w1_val |= (uint32_t)(qspi_cmd_struct->second_dummy_cycle_num << 16); + w1_val |= (uint32_t)(qspi_cmd_struct->instruction_length << 24); + w1_val |= (uint32_t)(qspi_cmd_struct->pe_mode_enable << 28); + qspi_x->cmd_w1 = w1_val; + + /* config analyse cmd_w2 register */ + qspi_x->cmd_w2 = (uint32_t)qspi_cmd_struct->data_counter; + + /* config analyse cmd_w3 register */ + w3_val = (uint32_t)(qspi_cmd_struct->write_data_enable << 1); + w3_val |= (uint32_t)(qspi_cmd_struct->read_status_enable << 2); + w3_val |= (uint32_t)(qspi_cmd_struct->read_status_config << 3); + w3_val |= (uint32_t)(qspi_cmd_struct->operation_mode << 5); + w3_val |= (uint32_t)(qspi_cmd_struct->pe_mode_operate_code << 16); + w3_val |= (uint32_t)(qspi_cmd_struct->instruction_code << 24); + qspi_x->cmd_w3 = w3_val; +} + +/** + * @brief initial xip mode for qspi_x + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param xip_init_struct: pointer to xip init structure. + * @retval none. + */ +void qspi_xip_init(qspi_type* qspi_x, qspi_xip_type* xip_init_struct) +{ + uint32_t xc0_val = 0, xc1_val = 0, xc2_val = 0; + /* config analyse xip_cmd_w0 register */ + xc0_val = (uint32_t)xip_init_struct->read_second_dummy_cycle_num; + xc0_val |= (uint32_t)(xip_init_struct->read_operation_mode << 8); + xc0_val |= (uint32_t)(xip_init_struct->read_address_length << 11); + xc0_val |= (uint32_t)(xip_init_struct->read_instruction_code << 12); + qspi_x->xip_cmd_w0 = xc0_val; + + /* config analyse xip_cmd_w1 register */ + xc1_val = (uint32_t)xip_init_struct->write_second_dummy_cycle_num; + xc1_val |= (uint32_t)(xip_init_struct->write_operation_mode << 8); + xc1_val |= (uint32_t)(xip_init_struct->write_address_length << 11); + xc1_val |= (uint32_t)(xip_init_struct->write_instruction_code << 12); + qspi_x->xip_cmd_w1 = xc1_val; + + /* config analyse xip_cmd_w2 register */ + xc2_val = (uint32_t)xip_init_struct->read_data_counter; + xc2_val |= (uint32_t)(xip_init_struct->read_time_counter << 8); + xc2_val |= (uint32_t)(xip_init_struct->read_select_mode << 15); + xc2_val |= (uint32_t)(xip_init_struct->write_data_counter << 16); + xc2_val |= (uint32_t)(xip_init_struct->write_time_counter << 24); + xc2_val |= (uint32_t)(xip_init_struct->write_select_mode << 31); + qspi_x->xip_cmd_w2 = xc2_val; +} + +/** + * @brief read one byte from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 8-bit data. + */ +uint8_t qspi_byte_read(qspi_type* qspi_x) +{ + return qspi_x->dt_u8; +} + +/** + * @brief read one half-word from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 16-bit data. + */ +uint16_t qspi_half_word_read(qspi_type* qspi_x) +{ + return qspi_x->dt_u16; +} + +/** + * @brief read one word from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 32-bit data. + */ +uint32_t qspi_word_read(qspi_type* qspi_x) +{ + return qspi_x->dt; +} + +/** + * @brief write one byte to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 8-bit data. + * @retval none. + */ +void qspi_byte_write(qspi_type* qspi_x, uint8_t value) +{ + qspi_x->dt_u8 = value; +} + +/** + * @brief write one half-word to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 16-bit data. + * @retval none. + */ +void qspi_half_word_write(qspi_type* qspi_x, uint16_t value) +{ + qspi_x->dt_u16 = value; +} + +/** + * @brief write one word to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 32-bit data. + * @retval none. + */ +void qspi_word_write(qspi_type* qspi_x, uint32_t value) +{ + qspi_x->dt = value; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c new file mode 100644 index 0000000000..3728c2dfb6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c @@ -0,0 +1,220 @@ +/** + ************************************************************************** + * @file at32f435_437_scfg.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the system config firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SCFG + * @brief SCFG driver modules + * @{ + */ + +#ifdef SCFG_MODULE_ENABLED + +/** @defgroup SCFG_private_functions + * @{ + */ + +/** + * @brief scfg reset + * @param none + * @retval none + */ +void scfg_reset(void) +{ + crm_periph_reset(CRM_SCFG_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SCFG_PERIPH_RESET, FALSE); +} + +/** + * @brief scfg xmc address mapping swap set + * @param xmc_swap + * this parameter can be one of the following values: + * - SCFG_XMC_SWAP_NONE + * - SCFG_XMC_SWAP_MODE1 + * - SCFG_XMC_SWAP_MODE2 + * - SCFG_XMC_SWAP_MODE3 + * @retval none + */ +void scfg_xmc_mapping_swap_set(scfg_xmc_swap_type xmc_swap) +{ + SCFG->cfg1_bit.swap_xmc = xmc_swap; +} + +/** + * @brief scfg infrared config + * @param source + * this parameter can be one of the following values: + * - SCFG_IR_SOURCE_TMR10 + * - SCFG_IR_SOURCE_USART1 + * - SCFG_IR_SOURCE_USART2 + * @param polarity + * this parameter can be one of the following values: + * - SCFG_IR_POLARITY_NO_AFFECTE + * - SCFG_IR_POLARITY_REVERSE + * @retval none + */ +void scfg_infrared_config(scfg_ir_source_type source, scfg_ir_polarity_type polarity) +{ + SCFG->cfg1_bit.ir_src_sel = source; + SCFG->cfg1_bit.ir_pol = polarity; +} + +/** + * @brief scfg memory address mapping set + * @param mem_map + * this parameter can be one of the following values: + * - SCFG_MEM_MAP_MAIN_MEMORY + * - SCFG_MEM_MAP_BOOT_MEMORY + * - SCFG_MEM_MAP_XMC_BANK1 + * - SCFG_MEM_MAP_INTERNAL_SRAM + * - SCFG_MEM_MAP_XMC_SDRAM_BANK1 + * @retval none + */ +void scfg_mem_map_set(scfg_mem_map_type mem_map) +{ + SCFG->cfg1_bit.mem_map_sel = mem_map; +} + +/** + * @brief scfg emac interface set + * @param mode + * this parameter can be one of the following values: + * - SCFG_EMAC_SELECT_MII + * - SCFG_EMAC_SELECT_RMII + * @retval none + */ +void scfg_emac_interface_set(scfg_emac_interface_type mode) +{ + SCFG->cfg2_bit.mii_rmii_sel = mode; +} + +/** + * @brief select the gpio pin used as exint line. + * @param port_source: + * select the gpio port to be used as source for exint lines. + * this parameter can be one of the following values: + * - SCFG_PORT_SOURCE_GPIOA + * - SCFG_PORT_SOURCE_GPIOB + * - SCFG_PORT_SOURCE_GPIOC + * - SCFG_PORT_SOURCE_GPIOD + * - SCFG_PORT_SOURCE_GPIOE + * - SCFG_PORT_SOURCE_GPIOF + * - SCFG_PORT_SOURCE_GPIOG + * - SCFG_PORT_SOURCE_GPIOH + * @param pin_source: + * specifies the exint line to be configured. + * this parameter can be one of the following values: + * - SCFG_PINS_SOURCE0 + * - SCFG_PINS_SOURCE1 + * - SCFG_PINS_SOURCE2 + * - SCFG_PINS_SOURCE3 + * - SCFG_PINS_SOURCE4 + * - SCFG_PINS_SOURCE5 + * - SCFG_PINS_SOURCE6 + * - SCFG_PINS_SOURCE7 + * - SCFG_PINS_SOURCE8 + * - SCFG_PINS_SOURCE9 + * - SCFG_PINS_SOURCE10 + * - SCFG_PINS_SOURCE11 + * - SCFG_PINS_SOURCE12 + * - SCFG_PINS_SOURCE13 + * - SCFG_PINS_SOURCE14 + * - SCFG_PINS_SOURCE15 + * @retval none + */ +void scfg_exint_line_config(scfg_port_source_type port_source, scfg_pins_source_type pin_source) +{ + uint32_t tmp = 0x00; + tmp = ((uint32_t)0x0F) << (0x04 * (pin_source & (uint8_t)0x03)); + + switch (pin_source >> 0x02) + { + case 0: + SCFG->exintc1 &= ~tmp; + SCFG->exintc1 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 1: + SCFG->exintc2 &= ~tmp; + SCFG->exintc2 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 2: + SCFG->exintc3 &= ~tmp; + SCFG->exintc3 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 3: + SCFG->exintc4 &= ~tmp; + SCFG->exintc4 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + default: + break; + } +} + +/** + * @brief enable or disable gpio pins ultra driven. + * @param value: + * this parameter can be one of the following values: + * - SCFG_ULTRA_DRIVEN_PB3 + * - SCFG_ULTRA_DRIVEN_PB9 + * - SCFG_ULTRA_DRIVEN_PB10 + * - SCFG_ULTRA_DRIVEN_PD12 + * - SCFG_ULTRA_DRIVEN_PD13 + * - SCFG_ULTRA_DRIVEN_PD14 + * - SCFG_ULTRA_DRIVEN_PD15 + * - SCFG_ULTRA_DRIVEN_PF14 + * - SCFG_ULTRA_DRIVEN_PF15 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void scfg_pins_ultra_driven_enable(scfg_ultra_driven_pins_type value, confirm_state new_state) +{ + if(TRUE == new_state) + { + SCFG_REG(value) |= SCFG_REG_BIT(value); + } + else + { + SCFG_REG(value) &= ~(SCFG_REG_BIT(value)); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c new file mode 100644 index 0000000000..2cff6dc727 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c @@ -0,0 +1,575 @@ +/** + ************************************************************************** + * @file at32f435_437_sdio.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the sdio firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +#ifdef SDIO_MODULE_ENABLED + +/** @defgroup SDIO_private_functions + * @{ + */ + +/** + * @brief reset the sdio register + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval none + */ +void sdio_reset(sdio_type *sdio_x) +{ + sdio_x->pwrctrl = 0x0; + sdio_x->clkctrl = 0x0; + sdio_x->argu = 0x0; + sdio_x->cmdctrl = 0x0; + sdio_x->dttmr = 0x0; + sdio_x->dtlen = 0x0; + sdio_x->dtctrl = 0x0; + sdio_x->inten = 0x0; + sdio_x->intclr = 0x004007FF; +} + +/** + * @brief set the power status of the controller + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param power_state + * this parameter can be one of the following values: + * - SDIO_POWER_OFF + * - SDIO_POWER_ON + * @retval none + */ +void sdio_power_set(sdio_type *sdio_x, sdio_power_state_type power_state) +{ + sdio_x->pwrctrl_bit.ps = power_state; +} + +/** + * @brief get power status. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval sdio_power_state_type (SDIO_POWER_ON or SDIO_POWER_OFF) + */ +sdio_power_state_type sdio_power_status_get(sdio_type *sdio_x) +{ + return (sdio_power_state_type)(sdio_x->pwrctrl_bit.ps); +} + +/** + * @brief config sdio clock + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param clk_div: sdio clock divide factor(frequency = sdio_clk / [clk_psc + 2]). + * @param clk_edg + * this parameter can be one of the following values: + * - SDIO_CLOCK_EDGE_RISING + * - SDIO_CLOCK_EDGE_FALLING + * @retval none + */ +void sdio_clock_config(sdio_type *sdio_x, uint16_t clk_div, sdio_edge_phase_type clk_edg) +{ + /* config clock edge */ + sdio_x->clkctrl_bit.clkegs = clk_edg; + + /* config clock divide [7:0] */ + sdio_x->clkctrl_bit.clkdiv_l = (clk_div & 0xFF); + + /* config clock divide [9:8] */ + sdio_x->clkctrl_bit.clkdiv_h = ((clk_div & 0x300) >> 8); +} + +/** + * @brief config sdio bus width + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param width + * this parameter can be one of the following values: + * - SDIO_BUS_WIDTH_D1 + * - SDIO_BUS_WIDTH_D4 + * - SDIO_BUS_WIDTH_D8 + * @retval none + */ +void sdio_bus_width_config(sdio_type *sdio_x, sdio_bus_width_type width) +{ + sdio_x->clkctrl_bit.busws = width; +} + +/** + * @brief enable or disable clock divider bypss + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_clock_bypass(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.bypsen = new_state; +} + +/** + * @brief enable or disable power saving mode, config sdio_ck clock output + * when the bus is idle. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_power_saving_mode_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.pwrsven = new_state; +} + +/** + * @brief enable or disable hardware flow control. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_flow_control_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.hfcen = new_state; +} + +/** + * @brief enable or disable sdio_ck output. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_clock_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.clkoen = new_state; +} + +/** + * @brief enable or disable dma. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_dma_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.dmaen = new_state; +} + +/** + * @brief config corresponding interrupt. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param int_opt + * this parameter can be one of the following values: + * - SDIO_CMDFAIL_INT + * - SDIO_DTFAIL_INT + * - SDIO_CMDTIMEOUT_INT + * - SDIO_DTTIMEOUT_INT + * - SDIO_TXERRU_INT + * - SDIO_RXERRO_INT + * - SDIO_CMDRSPCMPL_INT + * - SDIO_CMDCMPL_INT + * - SDIO_DTCMP_INT + * - SDIO_SBITERR_INT + * - SDIO_DTBLKCMPL_INT + * - SDIO_DOCMD_INT + * - SDIO_DOTX_INT + * - SDIO_DORX_INT + * - SDIO_TXBUFH_INT + * - SDIO_RXBUFH_INT + * - SDIO_TXBUFF_INT + * - SDIO_RXBUFF_INT + * - SDIO_TXBUFE_INT + * - SDIO_RXBUFE_INT + * - SDIO_TXBUF_INT + * - SDIO_RXBUF_INT + * - SDIO_SDIOIF_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_interrupt_enable(sdio_type *sdio_x, uint32_t int_opt, confirm_state new_state) +{ + /* enable interrupt */ + if(TRUE == new_state) + { + sdio_x->inten |= int_opt; + } + /* disable interrupt */ + else + { + sdio_x->inten &= ~(int_opt); + } +} + +/** + * @brief get sdio flag. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param flag + * this parameter can be one of the following values: + * - SDIO_CMDFAIL_FLAG + * - SDIO_DTFAIL_FLAG + * - SDIO_CMDTIMEOUT_FLAG + * - SDIO_DTTIMEOUT_FLAG + * - SDIO_TXERRU_FLAG + * - SDIO_RXERRO_FLAG + * - SDIO_CMDRSPCMPL_FLAG + * - SDIO_CMDCMPL_FLAG + * - SDIO_DTCMPL_FLAG + * - SDIO_SBITERR_FLAG + * - SDIO_DTBLKCMPL_FLAG + * - SDIO_DOCMD_FLAG + * - SDIO_DOTX_FLAG + * - SDIO_DORX_FLAG + * - SDIO_TXBUFH_FLAG + * - SDIO_RXBUFH_FLAG + * - SDIO_TXBUFF_FLAG + * - SDIO_RXBUFF_FLAG + * - SDIO_TXBUFE_FLAG + * - SDIO_RXBUFE_FLAG + * - SDIO_TXBUF_FLAG + * - SDIO_RXBUF_FLAG + * - SDIO_SDIOIF_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status sdio_flag_get(sdio_type *sdio_x, uint32_t flag) +{ + flag_status status = RESET; + + if((sdio_x->sts & flag) == flag) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief clear sdio flag. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param int_opt + * this parameter can be any combination of the following values: + * - SDIO_CMDFAIL_FLAG + * - SDIO_DTFAIL_FLAG + * - SDIO_CMDTIMEOUT_FLAG + * - SDIO_DTTIMEOUT_FLAG + * - SDIO_TXERRU_FLAG + * - SDIO_RXERRO_FLAG + * - SDIO_CMDRSPCMPL_FLAG + * - SDIO_CMDCMPL_FLAG + * - SDIO_DTCMPL_FLAG + * - SDIO_SBITERR_FLAG + * - SDIO_DTBLKCMPL_FLAG + * - SDIO_SDIOIF_FLAG + * @retval none + */ +void sdio_flag_clear(sdio_type *sdio_x, uint32_t flag) +{ + sdio_x->intclr = flag; +} + +/** + * @brief config sdio command. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param command_struct : pointer to a sdio_command_struct_type structure + * that contains the configuration information for the sdio command. + * @retval none + */ +void sdio_command_config(sdio_type *sdio_x, sdio_command_struct_type *command_struct) +{ + /* disable command path state machine */ + sdio_x->cmdctrl_bit.ccsmen = FALSE; + + /* config command argument */ + sdio_x->argu = command_struct->argument; + + /* config command register */ + sdio_x->cmdctrl_bit.cmdidx = command_struct->cmd_index; + sdio_x->cmdctrl_bit.rspwt = command_struct->rsp_type; + sdio_x->cmdctrl_bit.intwt = (command_struct->wait_type & 0x1); /* [1:0] -> [0] */ + sdio_x->cmdctrl_bit.pndwt = (command_struct->wait_type & 0x2)>>1; /* [1:0] -> [1] */ +} + +/** + * @brief enable or disable command path state machine(CPSM). + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_command_state_machine_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->cmdctrl_bit.ccsmen = new_state; +} + +/** + * @brief get command index of last command for which response received. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval uint8_t: command index + */ +uint8_t sdio_command_response_get(sdio_type *sdio_x) +{ + return sdio_x->rspcmd_bit.rspcmd; +} + +/** + * @brief get response received from the card for the last command. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param reg_index + * this parameter can be one of the following values: + * - SDIO_RSP1_INDEX + * - SDIO_RSP2_INDEX + * - SDIO_RSP3_INDEX + * - SDIO_RSP4_INDEX + * @retval uint32_t: response register value + */ +uint32_t sdio_response_get(sdio_type *sdio_x, sdio_rsp_index_type reg_index) +{ + uint32_t response_value = 0; + + switch(reg_index) + { + case SDIO_RSP1_INDEX: + response_value = sdio_x->rsp1; + break; + case SDIO_RSP2_INDEX: + response_value = sdio_x->rsp2; + break; + case SDIO_RSP3_INDEX: + response_value = sdio_x->rsp3; + break; + case SDIO_RSP4_INDEX: + response_value = sdio_x->rsp4; + break; + default: break; + } + + return response_value; +} + +/** + * @brief config sdio data. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param data_struct : pointer to a sdio_data_struct_type structure + * that contains the configuration information for the sdio data. + * @retval none + */ +void sdio_data_config(sdio_type *sdio_x, sdio_data_struct_type *data_struct) +{ + /* disable data path state machine */ + sdio_x->dtctrl_bit.tfren = FALSE; + + /* config data block, transfer mode and transfer direction */ + sdio_x->dtctrl_bit.blksize = data_struct->block_size; + sdio_x->dtctrl_bit.tfrdir = data_struct->transfer_direction; + sdio_x->dtctrl_bit.tfrmode = data_struct->transfer_mode; + + /* config data length */ + sdio_x->dtlen_bit.dtlen = data_struct->data_length; + + /* config data transfer timeout */ + sdio_x->dttmr_bit.timeout = data_struct->timeout; +} + +/** + * @brief enable or disable data path state machine(DPSM). + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_data_state_machine_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.tfren = new_state; +} + +/** + * @brief get the number of remaining data bytes to be transferred. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: number of bytes + */ +uint32_t sdio_data_counter_get(sdio_type *sdio_x) +{ + return sdio_x->dtcnt; +} + +/** + * @brief read a word data from sdio fifo. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: data received + */ +uint32_t sdio_data_read(sdio_type *sdio_x) +{ + return sdio_x->buf; +} + +/** + * @brief get the number of words left to be written to or read from fifo.. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: number of words + */ +uint32_t sdio_buffer_counter_get(sdio_type *sdio_x) +{ + return sdio_x->bufcnt; +} + +/** + * @brief write one word data to fifo. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param data: data to be transferred. + * @retval none + */ +void sdio_data_write(sdio_type *sdio_x, uint32_t data) +{ + sdio_x->buf = data; +} + +/** + * @brief set the read wait mode. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param mode + * this parameter can be one of the following values: + * - SDIO_READ_WAIT_CONTROLLED_BY_D2 + * - SDIO_READ_WAIT_CONTROLLED_BY_CK + * @retval none + */ +void sdio_read_wait_mode_set(sdio_type *sdio_x, sdio_read_wait_mode_type mode) +{ + sdio_x->dtctrl_bit.rdwtmode = mode; +} + +/** + * @brief enable or disable to start sd i/o read wait operation. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_read_wait_start(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.rdwtstart = new_state; +} + +/** + * @brief enable or disable to stop sd i/o read wait operation. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_read_wait_stop(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.rdwtstop = new_state; +} + +/** + * @brief enable or disable the sd i/o function. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_io_function_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.ioen = new_state; +} + +/** + * @brief enable or disable sd i/o suspend command sending. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_io_suspend_command_set(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->cmdctrl_bit.iosusp = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c new file mode 100644 index 0000000000..369c34fa23 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c @@ -0,0 +1,650 @@ +/** + ************************************************************************** + * @file at32f435_437_spi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the spi firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +#ifdef SPI_MODULE_ENABLED + +/** @defgroup SPI_private_functions + * @{ + */ + +/** + * @brief spi reset by crm reset register + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval none + */ +void spi_i2s_reset(spi_type *spi_x) +{ + if(spi_x == SPI1) + { + crm_periph_reset(CRM_SPI1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI1_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI2) + { + crm_periph_reset(CRM_SPI2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI2_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI3) + { + crm_periph_reset(CRM_SPI3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI3_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI4) + { + crm_periph_reset(CRM_SPI4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI4_PERIPH_RESET, FALSE); + } +} + +/** + * @brief spi init config with its default value. + * @param spi_init_struct : pointer to a spi_init_type structure which will + * be initialized. + * @retval none + */ +void spi_default_para_init(spi_init_type* spi_init_struct) +{ + spi_init_struct->transmission_mode = SPI_TRANSMIT_FULL_DUPLEX; + spi_init_struct->master_slave_mode = SPI_MODE_SLAVE; + spi_init_struct->mclk_freq_division = SPI_MCLK_DIV_2; + spi_init_struct->first_bit_transmission = SPI_FIRST_BIT_MSB; + spi_init_struct->frame_bit_num = SPI_FRAME_8BIT; + spi_init_struct->clock_polarity = SPI_CLOCK_POLARITY_LOW; + spi_init_struct->clock_phase = SPI_CLOCK_PHASE_1EDGE; + spi_init_struct->cs_mode_selection = SPI_CS_SOFTWARE_MODE; +} + +/** + * @brief spi init config with its setting value. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param spi_init_struct : pointer to a spi_init_type structure which will be initialized. + * @retval none + */ +void spi_init(spi_type* spi_x, spi_init_type* spi_init_struct) +{ + spi_x->i2sctrl_bit.i2smsel = FALSE; + if(spi_init_struct->transmission_mode == SPI_TRANSMIT_FULL_DUPLEX) + { + spi_x->ctrl1_bit.slben = FALSE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = FALSE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_SIMPLEX_RX) + { + spi_x->ctrl1_bit.slben = FALSE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = TRUE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_HALF_DUPLEX_RX) + { + spi_x->ctrl1_bit.slben = TRUE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = FALSE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_HALF_DUPLEX_TX) + { + spi_x->ctrl1_bit.slben = TRUE; + spi_x->ctrl1_bit.slbtd = TRUE; + spi_x->ctrl1_bit.ora = FALSE; + } + + spi_x->ctrl1_bit.swcsen = spi_init_struct->cs_mode_selection; + if((spi_init_struct->master_slave_mode == SPI_MODE_MASTER) && (spi_init_struct->cs_mode_selection == SPI_CS_SOFTWARE_MODE)) + { + spi_x->ctrl1_bit.swcsil = TRUE; + } + else + { + spi_x->ctrl1_bit.swcsil = FALSE; + } + spi_x->ctrl1_bit.msten = spi_init_struct->master_slave_mode; + + if(spi_init_struct->mclk_freq_division <= SPI_MCLK_DIV_256) + { + spi_x->ctrl2_bit.mdiv3en = FALSE; + spi_x->ctrl2_bit.mdiv_h = FALSE; + spi_x->ctrl1_bit.mdiv_l = spi_init_struct->mclk_freq_division; + } + else if(spi_init_struct->mclk_freq_division == SPI_MCLK_DIV_3) + { + spi_x->ctrl2_bit.mdiv3en = TRUE; + spi_x->ctrl2_bit.mdiv_h = FALSE; + spi_x->ctrl1_bit.mdiv_l = 0; + } + else + { + spi_x->ctrl2_bit.mdiv3en = FALSE; + spi_x->ctrl2_bit.mdiv_h = TRUE; + spi_x->ctrl1_bit.mdiv_l = spi_init_struct->mclk_freq_division & 0x7; + } + + spi_x->ctrl1_bit.ltf = spi_init_struct->first_bit_transmission; + spi_x->ctrl1_bit.fbn = spi_init_struct->frame_bit_num; + spi_x->ctrl1_bit.clkpol = spi_init_struct->clock_polarity; + spi_x->ctrl1_bit.clkpha = spi_init_struct->clock_phase; +} + +/** + * @brief enable or disable the ti mode for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of ti mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_ti_mode_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.tien = new_state; +} + +/** + * @brief spi next transmit crc for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval none + */ +void spi_crc_next_transmit(spi_type* spi_x) +{ + spi_x->ctrl1_bit.ntc = TRUE; +} + +/** + * @brief set the crc polynomial value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param crc_poly: crc polynomial value. + * @retval none + */ +void spi_crc_polynomial_set(spi_type* spi_x, uint16_t crc_poly) +{ + spi_x->cpoly_bit.cpoly = crc_poly; +} + +/** + * @brief return the crc polynomial register value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval the select crc polynomial register value + */ +uint16_t spi_crc_polynomial_get(spi_type* spi_x) +{ + return spi_x->cpoly_bit.cpoly; +} + +/** + * @brief enable or disable the hardware crc calculation for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of crc calculation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_crc_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl1_bit.ccen = new_state; +} + +/** + * @brief return the transmit or the receive crc value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param crc_direction: select transmit or receive crc value to be read + * - SPI_CRC_RX + * - SPI_CRC_TX + * @retval the select crc register value + */ +uint16_t spi_crc_value_get(spi_type* spi_x, spi_crc_direction_type crc_direction) +{ + if(crc_direction == SPI_CRC_RX) + return spi_x->rcrc_bit.rcrc; + else + return spi_x->tcrc_bit.tcrc; +} + +/** + * @brief enable or disable the hardware cs output for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of spi master cs output. + * this parameter can be: TRUE or FALSE. + * note:the bit only use in spi master mode + * @retval none + */ +void spi_hardware_cs_output_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.hwcsoe = new_state; +} + +/** + * @brief set the software cs internal level for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param level: set the state of spi cs level. + * this parameter can be one of the following values: + * - SPI_SWCS_INTERNAL_LEVEL_LOW + * - SPI_SWCS_INTERNAL_LEVEL_HIGHT + * note:the bit only use when swcsen bit is set. + * note:when use this bit,io operation on the cs pin are invalid. + * @retval none + */ +void spi_software_cs_internal_level_set(spi_type* spi_x, spi_software_cs_level_type level) +{ + spi_x->ctrl1_bit.swcsil = level; +} + +/** + * @brief set the data frame bit num for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param bit_num: set the data frame size + * - SPI_FRAME_8BIT + * - SPI_FRAME_16BIT + * @retval none + */ +void spi_frame_bit_num_set(spi_type* spi_x, spi_frame_bit_num_type bit_num) +{ + spi_x->ctrl1_bit.fbn = bit_num; +} + +/** + * @brief set the data transmission direction in single line bidirectiona half duplex mode of the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param direction: data transfer direction + * this parameter can be one of the following values: + * - SPI_HALF_DUPLEX_DIRECTION_RX + * - SPI_HALF_DUPLEX_DIRECTION_TX + * @retval none + */ +void spi_half_duplex_direction_set(spi_type* spi_x, spi_half_duplex_direction_type direction) +{ + spi_x->ctrl1_bit.slbtd = direction; +} + +/** + * @brief enable or disable spi. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of spi. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl1_bit.spien = new_state; +} + +/** + * @brief i2s init config with its default value. + * @param i2s_init_struct : pointer to a i2s_init_type structure which will + * be initialized. + * @retval none + */ +void i2s_default_para_init(i2s_init_type* i2s_init_struct) +{ + i2s_init_struct->operation_mode = I2S_MODE_SLAVE_TX; + i2s_init_struct->audio_protocol = I2S_AUDIO_PROTOCOL_PHILLIPS; + i2s_init_struct->audio_sampling_freq = I2S_AUDIO_FREQUENCY_DEFAULT; + i2s_init_struct->data_channel_format = I2S_DATA_16BIT_CHANNEL_16BIT; + i2s_init_struct->clock_polarity = I2S_CLOCK_POLARITY_LOW; + i2s_init_struct->mclk_output_enable = FALSE; +} + +/** + * @brief i2s init config with its setting value. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param i2s_init_struct : pointer to a i2s_init_type structure which will be initialized. + * @retval none + */ +void i2s_init(spi_type* spi_x, i2s_init_type* i2s_init_struct) +{ + crm_clocks_freq_type clocks_freq; + uint32_t i2s_sclk_index = 0; + uint32_t i2sdiv_index = 2, i2sodd_index = 0, frequency_index = 0; + + /* i2s audio frequency config */ + if(i2s_init_struct->audio_sampling_freq == I2S_AUDIO_FREQUENCY_DEFAULT) + { + i2sodd_index = 0; + i2sdiv_index = 2; + } + else + { + crm_clocks_freq_get(&clocks_freq); + i2s_sclk_index = clocks_freq.sclk_freq; + if((i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_SHORT) || (i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_LONG)) + { + if(i2s_init_struct->mclk_output_enable == TRUE) + { + frequency_index = (((i2s_sclk_index / 128) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + else + { + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + frequency_index = (((i2s_sclk_index / 16) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + else + frequency_index = (((i2s_sclk_index / 32) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + } + else + { + if(i2s_init_struct->mclk_output_enable == TRUE) + { + frequency_index = (((i2s_sclk_index / 256) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + else + { + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + frequency_index = (((i2s_sclk_index / 32) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + else + frequency_index = (((i2s_sclk_index / 64) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + } + } + frequency_index = frequency_index / 10; + i2sodd_index = frequency_index & (uint16_t)0x0001; + i2sdiv_index = (frequency_index - i2sodd_index) / 2; + if((i2sdiv_index < 2) || (i2sdiv_index > 0x03FF)) + { + i2sodd_index = 0; + i2sdiv_index = 2; + } + spi_x->i2sclk_bit.i2sodd = i2sodd_index; + if(i2sdiv_index > 0x00FF) + { + spi_x->i2sclk_bit.i2sdiv_h = (i2sdiv_index >> 8) & 0x0003; + spi_x->i2sclk_bit.i2sdiv_l = i2sdiv_index & 0x00FF; + } + else + { + spi_x->i2sclk_bit.i2sdiv_h = 0; + spi_x->i2sclk_bit.i2sdiv_l = i2sdiv_index; + } + + /* i2s audio_protocol set*/ + if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_LONG) + { + spi_x->i2sctrl_bit.pcmfssel = 1; + spi_x->i2sctrl_bit.stdsel = 3; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_SHORT) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 3; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_LSB) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 2; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_MSB) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 1; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PHILLIPS) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 0; + } + + /* i2s data_channel_format set*/ + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + { + spi_x->i2sctrl_bit.i2scbn = 0; + spi_x->i2sctrl_bit.i2sdbn = 0; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 0; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_24BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 1; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_32BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 2; + } + + spi_x->i2sctrl_bit.i2sclkpol = i2s_init_struct->clock_polarity; + spi_x->i2sclk_bit.i2smclkoe = i2s_init_struct->mclk_output_enable; + spi_x->i2sctrl_bit.opersel = i2s_init_struct->operation_mode; + spi_x->i2sctrl_bit.i2smsel = TRUE; +} + +/** + * @brief enable or disable i2s. + * @param spi_x: select the i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of i2s. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void i2s_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->i2sctrl_bit.i2sen = new_state; +} + +/** + * @brief enable or disable the specified spi/i2s interrupts. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_int: specifies the spi/i2s interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - SPI_I2S_ERROR_INT + * - SPI_I2S_RDBF_INT + * - SPI_I2S_TDBE_INT + * @param new_state: new state of the specified spi/i2s interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_interrupt_enable(spi_type* spi_x, uint32_t spi_i2s_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + spi_x->ctrl2 |= spi_i2s_int; + } + else + { + spi_x->ctrl2 &= ~spi_i2s_int; + } +} + +/** + * @brief enable or disable the spi/i2s dma transmitter mode. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of the dma request. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_dma_transmitter_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.dmaten = new_state; +} + +/** + * @brief enable or disable the spi/i2s dma receiver mode. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of the dma request. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_dma_receiver_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.dmaren = new_state; +} + +/** + * @brief spi/i2s data transmit + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param tx_data: the data to be transmit. + * this parameter can be: + * - (0x0000~0xFFFF) + * @retval none + */ +void spi_i2s_data_transmit(spi_type* spi_x, uint16_t tx_data) +{ + spi_x->dt = tx_data; +} + +/** + * @brief spi/i2s data receive + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @retval the received data value + */ +uint16_t spi_i2s_data_receive(spi_type* spi_x) +{ + return (uint16_t)spi_x->dt; +} + +/** + * @brief get flag of the specified spi/i2s peripheral. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_flag: select the spi/i2s flag + * this parameter can be one of the following values: + * - SPI_I2S_RDBF_FLAG + * - SPI_I2S_TDBE_FLAG + * - I2S_ACS_FLAG (this flag only use in i2s mode) + * - I2S_TUERR_FLAG (this flag only use in i2s mode) + * - SPI_CCERR_FLAG (this flag only use in spi mode) + * - SPI_MMERR_FLAG (this flag only use in spi mode) + * - SPI_I2S_ROERR_FLAG + * - SPI_I2S_BF_FLAG + * - SPI_CSPAS_FLAG + * @retval the new state of spi/i2s flag + */ +flag_status spi_i2s_flag_get(spi_type* spi_x, uint32_t spi_i2s_flag) +{ + flag_status status = RESET; + if ((spi_x->sts & spi_i2s_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief clear flag of the specified spi/i2s peripheral. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_flag: select the spi/i2s flag + * this parameter can be one of the following values: + * - SPI_CCERR_FLAG + * - SPI_I2S_RDBF_FLAG + * - I2S_TUERR_FLAG + * - SPI_MMERR_FLAG + * - SPI_I2S_ROERR_FLAG + * - SPI_CSPAS_FLAG + * @note + * SPI_I2S_TDBE_FLAG this flag is cleared when the tx buffer already contain data to be transmit. + * I2S_ACS_FLAG this flag cann't cleared by software,the flag indicate the channel side(not use in pcm standard mode). + * SPI_I2S_BF_FLAG this flag cann't cleared by software, it's set and cleared by hardware. + * @retval none + */ +void spi_i2s_flag_clear(spi_type* spi_x, uint32_t spi_i2s_flag) +{ + if(spi_i2s_flag == SPI_CCERR_FLAG) + spi_x->sts = ~SPI_CCERR_FLAG; + else if(spi_i2s_flag == SPI_I2S_RDBF_FLAG) + UNUSED(spi_x->dt); + else if(spi_i2s_flag == I2S_TUERR_FLAG) + UNUSED(spi_x->sts); + else if(spi_i2s_flag == SPI_CSPAS_FLAG) + UNUSED(spi_x->sts); + else if(spi_i2s_flag == SPI_MMERR_FLAG) + { + UNUSED(spi_x->sts); + spi_x->ctrl1 = spi_x->ctrl1; + } + else if(spi_i2s_flag == SPI_I2S_ROERR_FLAG) + { + UNUSED(spi_x->dt); + UNUSED(spi_x->sts); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c new file mode 100644 index 0000000000..660e207d5d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c @@ -0,0 +1,1848 @@ +/** + ************************************************************************** + * @file at32f435_437_tmr.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the tmr firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup TMR + * @brief TMR driver modules + * @{ + */ + +#ifdef TMR_MODULE_ENABLED + +/** @defgroup TMR_private_functions + * @{ + */ + +/** + * @brief tmr reset by crm reset register + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval none + */ +void tmr_reset(tmr_type *tmr_x) +{ + if(tmr_x == TMR1) + { + crm_periph_reset(CRM_TMR1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR1_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR2) + { + crm_periph_reset(CRM_TMR2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR2_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR3) + { + crm_periph_reset(CRM_TMR3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR3_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR4) + { + crm_periph_reset(CRM_TMR4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR4_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR5) + { + crm_periph_reset(CRM_TMR5_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR5_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR6) + { + crm_periph_reset(CRM_TMR6_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR6_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR7) + { + crm_periph_reset(CRM_TMR7_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR7_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR8) + { + crm_periph_reset(CRM_TMR8_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR8_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR9) + { + crm_periph_reset(CRM_TMR9_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR9_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR10) + { + crm_periph_reset(CRM_TMR10_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR10_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR11) + { + crm_periph_reset(CRM_TMR11_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR11_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR12) + { + crm_periph_reset(CRM_TMR12_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR12_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR13) + { + crm_periph_reset(CRM_TMR13_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR13_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR14) + { + crm_periph_reset(CRM_TMR14_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR14_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR20) + { + crm_periph_reset(CRM_TMR20_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR20_PERIPH_RESET, FALSE); + } +} + +/** + * @brief enable or disable tmr counter + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_counter_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr counter enable */ + tmr_x->ctrl1_bit.tmren = new_state; +} + +/** + * @brief init tmr output default para + * @param tmr_output_struct + * - to the structure of tmr_output_config_type + * @retval none + */ +void tmr_output_default_para_init(tmr_output_config_type *tmr_output_struct) +{ + tmr_output_struct->oc_mode = TMR_OUTPUT_CONTROL_OFF; + tmr_output_struct->oc_idle_state = FALSE; + tmr_output_struct->occ_idle_state = FALSE; + tmr_output_struct->oc_polarity = TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct->occ_polarity = TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct->oc_output_state = FALSE; + tmr_output_struct->occ_output_state = FALSE; +} + +/** + * @brief init tmr input default para + * @param tmr_input_struct + * - to the structure of tmr_input_config_type + * @retval none + */ +void tmr_input_default_para_init(tmr_input_config_type *tmr_input_struct) +{ + tmr_input_struct->input_channel_select = TMR_SELECT_CHANNEL_1; + tmr_input_struct->input_polarity_select = TMR_INPUT_RISING_EDGE; + tmr_input_struct->input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_input_struct->input_filter_value = 0x0; +} + +/** + * @brief init tmr brkdt default para + * @param tmr_brkdt_struct + * - to the structure of tmr_brkdt_config_type + * @retval none + */ +void tmr_brkdt_default_para_init(tmr_brkdt_config_type *tmr_brkdt_struct) +{ + tmr_brkdt_struct->deadtime = 0x0; + tmr_brkdt_struct->brk_polarity = TMR_BRK_INPUT_ACTIVE_LOW; + tmr_brkdt_struct->wp_level = TMR_WP_OFF; + tmr_brkdt_struct->auto_output_enable = FALSE ; + tmr_brkdt_struct->fcsoen_state = FALSE ; + tmr_brkdt_struct->fcsodis_state = FALSE ; + tmr_brkdt_struct->brk_enable = FALSE ; +} + +/** + * @brief init tmr base + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_pr (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @param tmr_div (timer div value:0x0000~0xFFFF) + * @retval none + */ +void tmr_base_init(tmr_type* tmr_x, uint32_t tmr_pr, uint32_t tmr_div) +{ + /* set the pr value */ + tmr_x->pr = tmr_pr; + + /* set the div value */ + tmr_x->div = tmr_div; + + /* trigger the overflow event to immediately reload pr value and div value */ + tmr_x->swevt_bit.ovfswtr = TRUE; +} + +/** + * @brief set tmr clock source division + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_clock_div + * this parameter can be one of the following values: + * - TMR_CLOCK_DIV1 + * - TMR_CLOCK_DIV2 + * - TMR_CLOCK_DIV4 + * @retval none + */ +void tmr_clock_source_div_set(tmr_type *tmr_x, tmr_clock_division_type tmr_clock_div) +{ + /* set tmr clock source division */ + tmr_x->ctrl1_bit.clkdiv = tmr_clock_div; +} + +/** + * @brief set tmr counter count direction + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_cnt_dir + * this parameter can be one of the following values: + * - TMR_COUNT_UP + * - TMR_COUNT_DOWN + * - TMR_COUNT_TWO_WAY_1 + * - TMR_COUNT_TWO_WAY_2 + * - TMR_COUNT_TWO_WAY_3 + * @retval none + */ +void tmr_cnt_dir_set(tmr_type *tmr_x, tmr_count_mode_type tmr_cnt_dir) +{ + /* set the cnt direct */ + tmr_x->ctrl1_bit.cnt_dir = tmr_cnt_dir; +} + +/** + * @brief set the repetition counter register(rpr) value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param tmr_rpr_value (0x0000~0xFFFF) + * @retval none + */ +void tmr_repetition_counter_set(tmr_type *tmr_x, uint8_t tmr_rpr_value) +{ + /* set the repetition counter value */ + tmr_x->rpr_bit.rpr = tmr_rpr_value; +} + +/** + * @brief set tmr counter value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_cnt_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_counter_value_set(tmr_type *tmr_x, uint32_t tmr_cnt_value) +{ + /* set the tmr counter value */ + tmr_x->cval = tmr_cnt_value; +} + +/** + * @brief get tmr counter value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval tmr counter value + */ +uint32_t tmr_counter_value_get(tmr_type *tmr_x) +{ + return tmr_x->cval; +} + +/** + * @brief set tmr div value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_div_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_div_value_set(tmr_type *tmr_x, uint32_t tmr_div_value) +{ + /* set the tmr div value */ + tmr_x->div = tmr_div_value; +} + +/** + * @brief get tmr div value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval tmr div value + */ +uint32_t tmr_div_value_get(tmr_type *tmr_x) +{ + return tmr_x->div; +} + +/** + * @brief config tmr output channel + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param tmr_output_struct + * - to the structure of tmr_output_config_type + * @retval none + */ +void tmr_output_channel_config(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_config_type *tmr_output_struct) +{ + uint16_t channel_index = 0, channel_c_index = 0, channel = 0, chx_offset, chcx_offset; + + chx_offset = (8 + tmr_channel); + chcx_offset = (9 + tmr_channel); + + /* get channel idle state bit position in ctrl2 register */ + channel_index = (uint16_t)(tmr_output_struct->oc_idle_state << chx_offset); + + /* get channel complementary idle state bit position in ctrl2 register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_idle_state << chcx_offset); + + /* set output channel complementary idle state */ + tmr_x->ctrl2 &= ~(1<ctrl2 |= channel_c_index; + + /* set output channel idle state */ + tmr_x->ctrl2 &= ~(1<ctrl2 |= channel_index; + + /* set channel output mode */ + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = tmr_output_struct->oc_mode; + break; + + default: + break; + } + + chx_offset = ((tmr_channel * 2) + 1); + chcx_offset = ((tmr_channel * 2) + 3); + + /* get channel polarity bit position in cctrl register */ + channel_index = (uint16_t)(tmr_output_struct->oc_polarity << chx_offset); + + /* get channel complementary polarity bit position in cctrl register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_polarity << chcx_offset); + + /* set output channel complementary polarity */ + tmr_x->cctrl &= ~(1<cctrl |= channel_c_index; + + /* set output channel polarity */ + tmr_x->cctrl &= ~(1<cctrl |= channel_index; + + chx_offset = (tmr_channel * 2); + chcx_offset = ((tmr_channel * 2) + 2); + + /* get channel enable bit position in cctrl register */ + channel_index = (uint16_t)(tmr_output_struct->oc_output_state << (tmr_channel * 2)); + + /* get channel complementary enable bit position in cctrl register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_output_state << ((tmr_channel * 2) + 2)); + + /* set output channel complementary enable bit */ + tmr_x->cctrl &= ~(1<cctrl |= channel_c_index; + + /* set output channel enable bit */ + tmr_x->cctrl &= ~(1<cctrl |= channel_index; +} + +/** + * @brief select tmr output channel mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param oc_mode + * this parameter can be one of the following values: + * - TMR_OUTPUT_CONTROL_OFF + * - TMR_OUTPUT_CONTROL_HIGH + * - TMR_OUTPUT_CONTROL_LOW + * - TMR_OUTPUT_CONTROL_SWITCH + * - TMR_OUTPUT_CONTROL_FORCE_HIGH + * - TMR_OUTPUT_CONTROL_FORCE_LOW + * - TMR_OUTPUT_CONTROL_PWM_MODE_A + * - TMR_OUTPUT_CONTROL_PWM_MODE_B + * @retval none + */ +void tmr_output_channel_mode_select(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_control_mode_type oc_mode) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = oc_mode; + break; + + default: + break; + } +} +/** + * @brief set tmr period value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_pr_value: timer period register value of counter + * (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_period_value_set(tmr_type *tmr_x, uint32_t tmr_pr_value) +{ + /* set tmr period value */ + tmr_x->pr = tmr_pr_value; +} + +/** + * @brief get tmr period value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval timer period register value of counter + * (for 16 bit tmr 0x0000~0xFFFF, for 32 bit tmr + * 0x0000_0000~0xFFFF_FFFF) + */ +uint32_t tmr_period_value_get(tmr_type *tmr_x) +{ + return tmr_x->pr; +} + +/** + * @brief set tmr channel value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param tmr_channel_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_channel_value_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint32_t tmr_channel_value) +{ + uint16_t channel; + + channel = tmr_channel; + + /* set tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->c1dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->c2dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->c3dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->c4dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->c5dt = tmr_channel_value; + break; + + default: + break; + } +} + +/** + * @brief get tmr channel value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @retval tmr channel value + */ +uint32_t tmr_channel_value_get(tmr_type *tmr_x, tmr_channel_select_type tmr_channel) +{ + uint32_t cc_value_get = 0; + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + cc_value_get = tmr_x->c1dt; + break; + + case TMR_SELECT_CHANNEL_2: + cc_value_get = tmr_x->c2dt; + break; + + case TMR_SELECT_CHANNEL_3: + cc_value_get = tmr_x->c3dt; + break; + + case TMR_SELECT_CHANNEL_4: + cc_value_get = tmr_x->c4dt; + break; + + case TMR_SELECT_CHANNEL_5: + cc_value_get = tmr_x->c5dt; + break; + + default: + break; + } + + return cc_value_get; +} +/** + * @brief set tmr period buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_period_buffer_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr period buffer set */ + tmr_x->ctrl1_bit.prben = new_state; +} + +/** + * @brief set tmr output channel buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_buffer_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1oben = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2oben = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3oben = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4oben = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5oben = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr output channel immediately + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_immediately_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1oien = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2oien = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3oien = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4oien = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5oien = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr output channel switch + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_switch_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1osen = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2osen = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3osen = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4osen = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5osen = new_state; + break; + + default: + break; + } +} + +/** + * @brief enable or disable tmr one cycle mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, TMR9, TMR12, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_one_cycle_mode_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr one cycle mode enable */ + tmr_x->ctrl1_bit.ocmen = new_state; +} + +/** + * @brief enable or disable tmr 32 bit function(plus mode) + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR2, TMR5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_32_bit_function_enable (tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr 32 bit function(plus mode) enable,only for TMR2/TMR5 */ + if((tmr_x == TMR2) || (tmr_x == TMR5)) + { + tmr_x->ctrl1_bit.pmen = new_state; + } +} + +/** + * @brief select tmr the overflow event sources + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_overflow_request_source_set(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl1_bit.ovfs = new_state; +} + +/** + * @brief enable or disable tmr overflow event generation + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_overflow_event_disable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl1_bit.ovfen = new_state; +} + +/** + * @brief init tmr input channel + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param input_struct + * - to the structure of tmr_input_config_type + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_input_channel_init(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel = 0; + + /* get channel selected */ + channel = input_struct->input_channel_select; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1en = FALSE; + tmr_x->cctrl_bit.c1p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c1cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm1_input_bit.c1c = input_struct->input_mapped_select; + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cctrl_bit.c1en = TRUE; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2en = FALSE; + tmr_x->cctrl_bit.c2p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c2cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm1_input_bit.c2c = input_struct->input_mapped_select; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3en = FALSE; + tmr_x->cctrl_bit.c3p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c3cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm2_input_bit.c3c = input_struct->input_mapped_select; + tmr_x->cm2_input_bit.c3df = input_struct->input_filter_value; + tmr_x->cm2_input_bit.c3idiv = divider_factor; + tmr_x->cctrl_bit.c3en = TRUE; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4en = FALSE; + tmr_x->cctrl_bit.c4p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cm2_input_bit.c4c = input_struct->input_mapped_select; + tmr_x->cm2_input_bit.c4df = input_struct->input_filter_value; + tmr_x->cm2_input_bit.c4idiv = divider_factor; + tmr_x->cctrl_bit.c4en = TRUE; + break; + + default: + break; + } +} + +/** + * @brief tmr channel enable + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_1C + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_2C + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_3C + * - TMR_SELECT_CHANNEL_4 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_channel_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1en = new_state; + break; + + case TMR_SELECT_CHANNEL_1C: + tmr_x->cctrl_bit.c1cen = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2en = new_state; + break; + + case TMR_SELECT_CHANNEL_2C: + tmr_x->cctrl_bit.c2cen = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3en = new_state; + break; + + case TMR_SELECT_CHANNEL_3C: + tmr_x->cctrl_bit.c3cen = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4en = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr input channel filter + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * @param filter_value (0x0~0xf) + * @retval none + */ +void tmr_input_channel_filter_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint16_t filter_value) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_input_bit.c1df = filter_value; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_input_bit.c2df = filter_value; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_input_bit.c3df = filter_value; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_input_bit.c4df = filter_value; + break; + + default: + break; + } +} + +/** + * @brief config tmr pwm input + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param input_struct + * - to the structure of tmr_input_config_type + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_pwm_input_config(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel = 0; + + /* get channel selected */ + channel = input_struct->input_channel_select; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + if(input_struct->input_polarity_select == TMR_INPUT_RISING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c1p = TMR_INPUT_RISING_EDGE; + tmr_x->cctrl_bit.c2p = TMR_INPUT_FALLING_EDGE; + } + else if(input_struct->input_polarity_select == TMR_INPUT_FALLING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c1p = TMR_INPUT_FALLING_EDGE; + tmr_x->cctrl_bit.c2p = TMR_INPUT_RISING_EDGE; + } + + if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_DIRECT) + { + /* ic1 is mapped on ti1 */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + + /* ic1 is mapped on ti2 */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + } + else if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_INDIRECT) + { + /* ic1 is mapped on ti1 */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + + /* ic1 is mapped on ti2 */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; + } + + /* set input ch1 and ch2 filter value*/ + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + + /*set input ch1 and ch2 divider value*/ + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + + tmr_x->cctrl_bit.c1en = TRUE; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + case TMR_SELECT_CHANNEL_2: + if(input_struct->input_polarity_select == TMR_INPUT_RISING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c2p = TMR_INPUT_RISING_EDGE; + tmr_x->cctrl_bit.c1p = TMR_INPUT_FALLING_EDGE; + } + else if(input_struct->input_polarity_select == TMR_INPUT_FALLING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c2p = TMR_INPUT_FALLING_EDGE; + tmr_x->cctrl_bit.c1p = TMR_INPUT_RISING_EDGE; + } + + if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_DIRECT) + { + /* set mapped direct */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + } + else if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_INDIRECT) + { + /* set mapped direct */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + } + + /* set input ch1 and ch2 filter value*/ + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + + /*set input ch1 and ch2 divider value*/ + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + + tmr_x->cctrl_bit.c1en = TRUE; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + default: + break; + } +} + +/** + * @brief select tmr channel1 input + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param ch1_connect + * this parameter can be one of the following values: + * - TMR_CHANEL1_CONNECTED_C1IRAW + * - TMR_CHANEL1_2_3_CONNECTED_C1IRAW_XOR + * @retval none + */ +void tmr_channel1_input_select(tmr_type *tmr_x, tmr_channel1_input_connected_type ch1_connect) +{ + tmr_x->ctrl2_bit.c1insel = ch1_connect; +} + +/** + * @brief set tmr input channel divider + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_input_channel_divider_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_input_bit.c1idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_input_bit.c2idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_input_bit.c3idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_input_bit.c4idiv = divider_factor; + break; + + default: + break; + } +} + +/** + * @brief select tmr primary mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, TMR20 + * @param primary_mode + * this parameter can be one of the following values: + * - TMR_PRIMARY_SEL_RESET + * - TMR_PRIMARY_SEL_ENABLE + * - TMR_PRIMARY_SEL_OVERFLOW + * - TMR_PRIMARY_SEL_COMPARE + * - TMR_PRIMARY_SEL_C1ORAW + * - TMR_PRIMARY_SEL_C2ORAW + * - TMR_PRIMARY_SEL_C3ORAW + * - TMR_PRIMARY_SEL_C4ORAW + * @retval none + */ +void tmr_primary_mode_select(tmr_type *tmr_x, tmr_primary_select_type primary_mode) +{ + tmr_x->ctrl2_bit.ptos = primary_mode; +} + +/** + * @brief select tmr subordinate mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param sub_mode + * this parameter can be one of the following values: + * - TMR_SUB_MODE_DIABLE + * - TMR_SUB_ENCODER_MODE_A + * - TMR_SUB_ENCODER_MODE_B + * - TMR_SUB_ENCODER_MODE_C + * - TMR_SUB_RESET_MODE + * - TMR_SUB_HANG_MODE + * - TMR_SUB_TRIGGER_MODE + * - TMR_SUB_EXTERNAL_CLOCK_MODE_A + + * @retval none + */ +void tmr_sub_mode_select(tmr_type *tmr_x, tmr_sub_mode_select_type sub_mode) +{ + tmr_x->stctrl_bit.smsel = sub_mode; +} + +/** + * @brief select tmr channel dma + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param cc_dma_select + * this parameter can be one of the following values: + * - TMR_DMA_REQUEST_BY_CHANNEL + * - TMR_DMA_REQUEST_BY_OVERFLOW + * @retval none + */ +void tmr_channel_dma_select(tmr_type *tmr_x, tmr_dma_request_source_type cc_dma_select) +{ + tmr_x->ctrl2_bit.drs = cc_dma_select; +} + +/** + * @brief select tmr hall + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_hall_select(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.ccfs = new_state; +} + +/** + * @brief select tmr channel buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_channel_buffer_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.cbctrl = new_state; +} + +/** + * @brief select tmr trgout2 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_trgout2_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.trgout2en = new_state; +} + +/** + * @brief select tmr sub-trigger + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param trigger_select + * this parameter can be one of the following values: + * - TMR_SUB_INPUT_SEL_IS0 + * - TMR_SUB_INPUT_SEL_IS1 + * - TMR_SUB_INPUT_SEL_IS2 + * - TMR_SUB_INPUT_SEL_IS3 + * - TMR_SUB_INPUT_SEL_C1INC + * - TMR_SUB_INPUT_SEL_C1DF1 + * - TMR_SUB_INPUT_SEL_C2DF2 + * - TMR_SUB_INPUT_SEL_EXTIN + * @retval none + */ +void tmr_trigger_input_select(tmr_type *tmr_x, sub_tmr_input_sel_type trigger_select) +{ + tmr_x->stctrl_bit.stis = trigger_select; +} + +/** + * @brief set tmr subordinate synchronization mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_sub_sync_mode_set(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->stctrl_bit.sts = new_state; +} + +/** + * @brief enable or disable tmr dma request + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param dma_request + * this parameter can be one of the following values: + * - TMR_OVERFLOW_DMA_REQUEST + * - TMR_C1_DMA_REQUEST + * - TMR_C2_DMA_REQUEST + * - TMR_C3_DMA_REQUEST + * - TMR_C4_DMA_REQUEST + * - TMR_HALL_DMA_REQUEST + * - TMR_TRIGGER_DMA_REQUEST + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_dma_request_enable(tmr_type *tmr_x, tmr_dma_request_type dma_request, confirm_state new_state) +{ + if(new_state == TRUE) + { + tmr_x->iden |= dma_request; + } + else if(new_state == FALSE) + { + tmr_x->iden &= ~dma_request; + } +} + +/** + * @brief enable or disable tmr interrupt + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_interrupt + * this parameter can be one of the following values: + * - TMR_OVF_INT + * - TMR_C1_INT + * - TMR_C2_INT + * - TMR_C3_INT + * - TMR_C4_INT + * - TMR_HALL_INT + * - TMR_TRIGGER_INT + * - TMR_BRK_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_interrupt_enable(tmr_type *tmr_x, uint32_t tmr_interrupt, confirm_state new_state) +{ + if(new_state == TRUE) + { + tmr_x->iden |= tmr_interrupt; + } + else if(new_state == FALSE) + { + tmr_x->iden &= ~tmr_interrupt; + } +} + +/** + * @brief get tmr flag + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_flag + * this parameter can be one of the following values: + * - TMR_OVF_FLAG + * - TMR_C1_FLAG + * - TMR_C2_FLAG + * - TMR_C3_FLAG + * - TMR_C4_FLAG + * - TMR_C5_FLAG + * - TMR_HALL_FLAG + * - TMR_TRIGGER_FLAG + * - TMR_BRK_FLAG + * - TMR_C1_RECAPTURE_FLAG + * - TMR_C2_RECAPTURE_FLAG + * - TMR_C3_RECAPTURE_FLAG + * - TMR_C4_RECAPTURE_FLAG + * @retval state of tmr flag + */ +flag_status tmr_flag_get(tmr_type *tmr_x, uint32_t tmr_flag) +{ + flag_status status = RESET; + + if((tmr_x->ists & tmr_flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief clear tmr flag + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_flag + * this parameter can be any combination of the following values: + * - TMR_OVF_FLAG + * - TMR_C1_FLAG + * - TMR_C2_FLAG + * - TMR_C3_FLAG + * - TMR_C4_FLAG + * - TMR_C5_FLAG + * - TMR_HALL_FLAG + * - TMR_TRIGGER_FLAG + * - TMR_BRK_FLAG + * - TMR_C1_RECAPTURE_FLAG + * - TMR_C2_RECAPTURE_FLAG + * - TMR_C3_RECAPTURE_FLAG + * - TMR_C4_RECAPTURE_FLAG + * @retval none + */ +void tmr_flag_clear(tmr_type *tmr_x, uint32_t tmr_flag) +{ + tmr_x->ists = ~tmr_flag; +} + +/** + * @brief generate tmr event + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_event + * this parameter can be one of the following values: + * - TMR_OVERFLOW_SWTRIG + * - TMR_C1_SWTRIG + * - TMR_C2_SWTRIG + * - TMR_C3_SWTRIG + * - TMR_C4_SWTRIG + * - TMR_HALL_SWTRIG + * - TMR_TRIGGER_SWTRIG + * - TMR_BRK_SWTRIG + * @retval none + */ +void tmr_event_sw_trigger(tmr_type *tmr_x, tmr_event_trigger_type tmr_event) +{ + tmr_x->swevt |= tmr_event; +} + +/** + * @brief tmr output enable(oen),this function is important for advtm output enable + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->brk_bit.oen = new_state; +} + +/** + * @brief set tmr select internal clock + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @retval none + */ +void tmr_internal_clock_set(tmr_type *tmr_x) +{ + tmr_x->stctrl_bit.smsel = TMR_SUB_MODE_DIABLE; +} + +/** + * @brief set tmr output channel polarity + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_1C + * - TMR_SELECT_CHANNEL_2C + * - TMR_SELECT_CHANNEL_3C + * @param oc_polarity + * this parameter can be one of the following values: + * - TMR_POLARITY_ACTIVE_HIGH + * - TMR_POLARITY_ACTIVE_LOW + * @retval none + */ +void tmr_output_channel_polarity_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_polarity_active_type oc_polarity) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_1C: + tmr_x->cctrl_bit.c1cp = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_2C: + tmr_x->cctrl_bit.c2cp = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_3C: + tmr_x->cctrl_bit.c3cp = (uint32_t)oc_polarity; + break; + + default: + break; + } +} + +/** + * @brief config tmr external clock + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_x->stctrl_bit.esdiv = es_divide; + tmr_x->stctrl_bit.esp = es_polarity; + tmr_x->stctrl_bit.esf = es_filter; +} + +/** + * @brief config tmr external clock mode1 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_mode1_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_external_clock_config(tmr_x, es_divide, es_polarity, es_filter); + tmr_x->stctrl_bit.smsel = TMR_SUB_EXTERNAL_CLOCK_MODE_A; + tmr_x->stctrl_bit.stis = TMR_SUB_INPUT_SEL_EXTIN; +} + +/** + * @brief config tmr external clock mode2 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_mode2_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_external_clock_config(tmr_x, es_divide, es_polarity, es_filter); + tmr_x->stctrl_bit.ecmben = TRUE; +} + +/** + * @brief config tmr encoder mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param encoder_mode + * this parameter can be one of the following values: + * - TMR_ENCODER_MODE_A + * - TMR_ENCODER_MODE_B + * - TMR_ENCODER_MODE_C + * @param ic1_polarity + * this parameter can be one of the following values: + * - TMR_INPUT_RISING_EDGE + * - TMR_INPUT_FALLING_EDGE + * - TMR_INPUT_BOTH_EDGE + * @param ic2_polarity + * this parameter can be one of the following values: + * - TMR_INPUT_RISING_EDGE + * - TMR_INPUT_FALLING_EDGE + * - TMR_INPUT_BOTH_EDGE + * @retval none + */ +void tmr_encoder_mode_config(tmr_type *tmr_x, tmr_encoder_mode_type encoder_mode, tmr_input_polarity_type \ + ic1_polarity, tmr_input_polarity_type ic2_polarity) +{ + tmr_x->stctrl_bit.smsel = encoder_mode; + + /* set ic1 polarity */ + tmr_x->cctrl_bit.c1p = (ic1_polarity & 0x1); + tmr_x->cctrl_bit.c1cp = (ic1_polarity >> 1); + /* set ic1 as input channel */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + + /* set ic2 polarity */ + tmr_x->cctrl_bit.c2p = (ic2_polarity & 0x1); + tmr_x->cctrl_bit.c2cp = (ic2_polarity >> 1); + /* set ic2 as input channel */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; +} + +/** + * @brief set tmr force output + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param force_output + * this parameter can be one of the following values: + * - TMR_FORCE_OUTPUT_HIGH + * - TMR_FORCE_OUTPUT_LOW + * @retval none + */ +void tmr_force_output_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_force_output_type force_output) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = force_output; + break; + + default: + break; + } +} + +/** + * @brief config tmr dma control + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param dma_length + * this parameter can be one of the following values: + * - TMR_DMA_TRANSFER_1BYTE + * - TMR_DMA_TRANSFER_2BYTES + * - TMR_DMA_TRANSFER_3BYTES + * ... + * - TMR_DMA_TRANSFER_17BYTES + * - TMR_DMA_TRANSFER_18BYTES + * @param dma_base_address + * this parameter can be one of the following values: + * - TMR_CTRL1_ADDRESS + * - TMR_CTRL2_ADDRESS + * - TMR_STCTRL_ADDRESS + * - TMR_IDEN_ADDRESS + * - TMR_ISTS_ADDRESS + * - TMR_SWEVT_ADDRESS + * - TMR_CM1_ADDRESS + * - TMR_CM2_ADDRESS + * - TMR_CCTRL_ADDRESS + * - TMR_CVAL_ADDRESS + * - TMR_DIV_ADDRESS + * - TMR_PR_ADDRESS + * - TMR_RPR_ADDRESS + * - TMR_C1DT_ADDRESS + * - TMR_C2DT_ADDRESS + * - TMR_C3DT_ADDRESS + * - TMR_C4DT_ADDRESS + * - TMR_BRK_ADDRESS + * - TMR_DMACTRL_ADDRESS + * @retval none + */ +void tmr_dma_control_config(tmr_type *tmr_x, tmr_dma_transfer_length_type dma_length, \ + tmr_dma_address_type dma_base_address) +{ + tmr_x->dmactrl_bit.dtb = dma_length; + tmr_x->dmactrl_bit.addr = dma_base_address; +} + +/** + * @brief config tmr break mode and dead-time + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param brkdt_struct + * - to the structure of tmr_brkdt_config_type + * @retval none + */ +void tmr_brkdt_config(tmr_type *tmr_x, tmr_brkdt_config_type *brkdt_struct) +{ + tmr_x->brk_bit.brken = brkdt_struct->brk_enable; + tmr_x->brk_bit.dtc = brkdt_struct->deadtime; + tmr_x->brk_bit.fcsodis = brkdt_struct->fcsodis_state; + tmr_x->brk_bit.fcsoen = brkdt_struct->fcsoen_state; + tmr_x->brk_bit.brkv = brkdt_struct->brk_polarity; + tmr_x->brk_bit.aoen = brkdt_struct->auto_output_enable; + tmr_x->brk_bit.wpc = brkdt_struct->wp_level; +} + +/** + * @brief set tmr2/tmr5 input channel remap + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR2, TMR5 + * @param input_remap + * - TMR2_TMR8TRGOUT_TMR5_GPIO + * - TMR2_PTP_TMR5_LICK + * - TMR2_OTG1FS_TMR5_LEXT + * - TMR2_OTG2FS_TMR5_ERTC + * @retval none + */ +void tmr_iremap_config(tmr_type *tmr_x, tmr_input_remap_type input_remap) +{ + if(tmr_x == TMR2) + { + tmr_x->rmp_bit.tmr2_ch1_irmp = input_remap; + } + else if(tmr_x == TMR5) + { + tmr_x->rmp_bit.tmr5_ch4_irmp = input_remap; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c new file mode 100644 index 0000000000..eb3b75282f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c @@ -0,0 +1,732 @@ +/** + ************************************************************************** + * @file at32f435_437_usart.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the usart firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +#ifdef USART_MODULE_ENABLED + +/** @defgroup USART_private_functions + * @{ + */ + +/** + * @brief deinitialize the usart peripheral registers to their default reset values. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @retval none + */ +void usart_reset(usart_type* usart_x) +{ + if(usart_x == USART1) + { + crm_periph_reset(CRM_USART1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART1_PERIPH_RESET, FALSE); + } + else if(usart_x == USART2) + { + crm_periph_reset(CRM_USART2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART2_PERIPH_RESET, FALSE); + } + else if(usart_x == USART3) + { + crm_periph_reset(CRM_USART3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART3_PERIPH_RESET, FALSE); + } + else if(usart_x == UART4) + { + crm_periph_reset(CRM_UART4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART4_PERIPH_RESET, FALSE); + } + else if(usart_x == UART5) + { + crm_periph_reset(CRM_UART5_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART5_PERIPH_RESET, FALSE); + } + else if(usart_x == USART6) + { + crm_periph_reset(CRM_USART6_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART6_PERIPH_RESET, FALSE); + } + else if(usart_x == UART7) + { + crm_periph_reset(CRM_UART7_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART7_PERIPH_RESET, FALSE); + } + else if(usart_x == UART8) + { + crm_periph_reset(CRM_UART8_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART8_PERIPH_RESET, FALSE); + } +} + +/** + * @brief initialize the usart peripheral according to the specified parameters. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param baud_rate: configure the usart communication baud rate. + * @param data_bit: data bits transmitted or received in a frame + * this parameter can be one of the following values: + * - USART_DATA_7BITS + * - USART_DATA_8BITS + * - USART_DATA_9BITS. + * @param stop_bit: stop bits transmitted + * this parameter can be one of the following values: + * - USART_STOP_1_BIT + * - USART_STOP_0_5_BIT. + * - USART_STOP_2_BIT + * - USART_STOP_1_5_BIT. + * @retval none + */ +void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit) +{ + crm_clocks_freq_type clocks_freq; + uint32_t apb_clock, temp_val; + crm_clocks_freq_get(&clocks_freq); + if((usart_x == USART1) || (usart_x == USART6)) + { + apb_clock = clocks_freq.apb2_freq; + } + else + { + apb_clock = clocks_freq.apb1_freq; + } + temp_val = (apb_clock * 10 / baud_rate); + if((temp_val % 10) < 5) + { + temp_val = (temp_val / 10); + } + else + { + temp_val = (temp_val / 10) + 1; + } + usart_x->baudr_bit.div = temp_val; + if(data_bit == USART_DATA_7BITS) + { + usart_x->ctrl1_bit.dbn_h = 1; + usart_x->ctrl1_bit.dbn_l = 0; + } + else if(data_bit == USART_DATA_8BITS) + { + usart_x->ctrl1_bit.dbn_h = 0; + usart_x->ctrl1_bit.dbn_l = 0; + } + else + { + usart_x->ctrl1_bit.dbn_h = 0; + usart_x->ctrl1_bit.dbn_l = 1; + } + usart_x->ctrl2_bit.stopbn = stop_bit; +} + +/** + * @brief usart parity selection config. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param parity: select the none, odd or even parity. + * this parameter can be one of the following values: + * - USART_PARITY_NONE + * - USART_PARITY_EVEN. + * - USART_PARITY_ODD + * @retval none + */ +void usart_parity_selection_config(usart_type* usart_x, usart_parity_selection_type parity) +{ + if(parity == USART_PARITY_NONE) + { + usart_x->ctrl1_bit.psel = FALSE; + usart_x->ctrl1_bit.pen = FALSE; + } + else if(parity == USART_PARITY_EVEN) + { + usart_x->ctrl1_bit.psel = FALSE; + usart_x->ctrl1_bit.pen = TRUE; + } + else if(parity == USART_PARITY_ODD) + { + usart_x->ctrl1_bit.psel = TRUE; + usart_x->ctrl1_bit.pen = TRUE; + } +} + +/** + * @brief enable or disable the specified usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart peripheral. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.uen = new_state; +} + +/** + * @brief usart transmitter enable. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void usart_transmitter_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.ten = new_state; +} + +/** + * @brief usart receiver enable. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void usart_receiver_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.ren = new_state; +} + +/** + * @brief usart clock config. + * @note clock config are not available for UART4, UART5, UART7 and UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param clk_pol: polarity of the clock output on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_POLARITY_LOW + * - USART_CLOCK_POLARITY_HIGH + * @param clk_pha: phase of the clock output on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_PHASE_1EDGE + * - USART_CLOCK_PHASE_2EDGE + * @param clk_lb: whether the clock pulse of the last data bit transmitted (MSB) is outputted on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_LAST_BIT_NONE + * - USART_CLOCK_LAST_BIT_OUTPUT + * @retval none + */ +void usart_clock_config(usart_type* usart_x, usart_clock_polarity_type clk_pol, usart_clock_phase_type clk_pha, usart_lbcp_type clk_lb) +{ + usart_x->ctrl2_bit.clkpol = clk_pol; + usart_x->ctrl2_bit.clkpha = clk_pha; + usart_x->ctrl2_bit.lbcp = clk_lb; +} + +/** + * @brief usart enable the ck pin. + * @note clock enable are not available for UART4, UART5, UART7 and UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: TRUE or FALSE + * @retval none + */ +void usart_clock_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.clken = new_state; +} + +/** + * @brief enable or disable the specified usart interrupts. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param usart_int: specifies the USART interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - USART_IDLE_INT: idle interrupt + * - USART_RDBF_INT: rdbf interrupt + * - USART_TDC_INT: tdc interrupt + * - USART_TDBE_INT: tdbe interrupt + * - USART_PERR_INT: perr interrupt + * - USART_BF_INT: break frame interrupt + * - USART_ERR_INT: err interrupt + * - USART_CTSCF_INT: ctscf interrupt + * @param new_state: new state of the specified usart interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_interrupt_enable(usart_type* usart_x, uint32_t usart_int, confirm_state new_state) +{ + if(new_state == TRUE) + PERIPH_REG((uint32_t)usart_x, usart_int) |= PERIPH_REG_BIT(usart_int); + else + PERIPH_REG((uint32_t)usart_x, usart_int) &= ~PERIPH_REG_BIT(usart_int); +} + +/** + * @brief enable or disable the usart's dma transmitter interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the dma request sources. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_dma_transmitter_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.dmaten = new_state; +} + +/** + * @brief enable or disable the usart's dma receiver interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the dma request sources. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_dma_receiver_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.dmaren = new_state; +} + +/** + * @brief set the wakeup id of the usart. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param usart_id: the matching id(0x0~0xFF). + * @retval none + */ +void usart_wakeup_id_set(usart_type* usart_x, uint8_t usart_id) +{ + if(usart_x->ctrl2_bit.idbn == USART_ID_FIXED_4_BIT) + { + usart_x->ctrl2_bit.id_l = (usart_id & 0x0F); + usart_x->ctrl2_bit.id_h = 0; + } + else + { + usart_x->ctrl2_bit.id_l = (usart_id & 0x0F); + usart_x->ctrl2_bit.id_h = ((usart_id & 0xF0) >> 4); + } +} + +/** + * @brief select the usart wakeup method in multi-processor communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param wakeup_mode: determines the way to wake up usart method. + * this parameter can be one of the following values: + * - USART_WAKEUP_BY_IDLE_FRAME + * - USART_WAKEUP_BY_MATCHING_ID + * @retval none + */ +void usart_wakeup_mode_set(usart_type* usart_x, usart_wakeup_mode_type wakeup_mode) +{ + usart_x->ctrl1_bit.wum = wakeup_mode; +} + +/** + * @brief config the usart in mute mode in multi-processor communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart mute mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_receiver_mute_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.rm = new_state; +} + +/** + * @brief set the usart break frame bit num. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param break_bit: specifies the break bit num. + * this parameter can be one of the following values: + * - USART_BREAK_10BITS + * - USART_BREAK_11BITS + * @retval none + */ +void usart_break_bit_num_set(usart_type* usart_x, usart_break_bit_num_type break_bit) +{ + usart_x->ctrl2_bit.bfbn = break_bit; +} + +/** + * @brief enable or disable the usart lin mode. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart lin mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_lin_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.linen = new_state; +} + +/** + * @brief transmit single data through the usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param data: the data to transmit. + * @retval none + */ +void usart_data_transmit(usart_type* usart_x, uint16_t data) +{ + usart_x->dt = (data & 0x01FF); +} + +/** + * @brief return the most recent received data by the usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @retval the received data. + */ +uint16_t usart_data_receive(usart_type* usart_x) +{ + return (uint16_t)(usart_x->dt); +} + +/** + * @brief transmit break characters. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @retval none + */ +void usart_break_send(usart_type* usart_x) +{ + usart_x->ctrl1_bit.sbf = TRUE; +} + +/** + * @brief config the specified usart smartcard guard time. + * @note The guard time bits are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param guard_time_val: specifies the guard time (0x00~0xFF). + * @retval none + */ +void usart_smartcard_guard_time_set(usart_type* usart_x, uint8_t guard_time_val) +{ + usart_x->gdiv_bit.scgt = guard_time_val; +} + +/** + * @brief config the irda/smartcard division. + * @note the division are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param div_val: specifies the division. + * @retval none + */ +void usart_irda_smartcard_division_set(usart_type* usart_x, uint8_t div_val) +{ + usart_x->gdiv_bit.isdiv = div_val; +} + +/** + * @brief enable or disable the usart smart card mode. + * @note the smart card mode are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: new state of the smart card mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_smartcard_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.scmen = new_state; +} + +/** + * @brief enable or disable nack transmission in smartcard mode. + * @note the smart card nack are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: new state of the nack transmission. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_smartcard_nack_set(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.scnacken = new_state; +} + +/** + * @brief enable or disable the usart single line bidirectional half-duplex communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the single line half-duplex select. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_single_line_halfduplex_select(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.slben = new_state; +} + +/** + * @brief enable or disable the usart's irda interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_irda_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.irdaen = new_state; +} + +/** + * @brief configure the usart's irda low power. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_irda_low_power_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.irdalp = new_state; +} + +/** + * @brief configure the usart's hardware flow control. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param flow_state: specifies the hardware flow control. + * this parameter can be one of the following values: + * - USART_HARDWARE_FLOW_NONE + * - USART_HARDWARE_FLOW_RTS, + * - USART_HARDWARE_FLOW_CTS, + * - USART_HARDWARE_FLOW_RTS_CTS + * @retval none + */ +void usart_hardware_flow_control_set(usart_type* usart_x,usart_hardware_flow_control_type flow_state) +{ + if(flow_state == USART_HARDWARE_FLOW_NONE) + { + usart_x->ctrl3_bit.rtsen = FALSE; + usart_x->ctrl3_bit.ctsen = FALSE; + } + else if(flow_state == USART_HARDWARE_FLOW_RTS) + { + usart_x->ctrl3_bit.rtsen = TRUE; + usart_x->ctrl3_bit.ctsen = FALSE; + } + else if(flow_state == USART_HARDWARE_FLOW_CTS) + { + usart_x->ctrl3_bit.rtsen = FALSE; + usart_x->ctrl3_bit.ctsen = TRUE; + } + else if(flow_state == USART_HARDWARE_FLOW_RTS_CTS) + { + usart_x->ctrl3_bit.rtsen = TRUE; + usart_x->ctrl3_bit.ctsen = TRUE; + } +} + +/** + * @brief check whether the specified usart flag is set or not. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - USART_CTSCF_FLAG: cts change flag (not available for UART4,UART5,USART6,UART7 and UART8) + * - USART_BFF_FLAG: break frame flag + * - USART_TDBE_FLAG: transmit data buffer empty flag + * - USART_TDC_FLAG: transmit data complete flag + * - USART_RDBF_FLAG: receive data buffer full flag + * - USART_IDLEF_FLAG: idle flag + * - USART_ROERR_FLAG: receiver overflow error flag + * - USART_NERR_FLAG: noise error flag + * - USART_FERR_FLAG: framing error flag + * - USART_PERR_FLAG: parity error flag + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status usart_flag_get(usart_type* usart_x, uint32_t flag) +{ + if(usart_x->sts & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear the usart's pending flags. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - USART_CTSCF_FLAG: (not available for UART4,UART5,USART6,UART7 and UART8). + * - USART_BFF_FLAG: + * - USART_TDC_FLAG: + * - USART_RDBF_FLAG: + * - USART_PERR_FLAG: + * - USART_FERR_FLAG: + * - USART_NERR_FLAG: + * - USART_ROERR_FLAG: + * - USART_IDLEF_FLAG: + * @note + * - USART_PERR_FLAG, USART_FERR_FLAG, USART_NERR_FLAG, USART_ROERR_FLAG and USART_IDLEF_FLAG are cleared by software + * sequence: a read operation to usart sts register (usart_flag_get()) + * followed by a read operation to usart dt register (usart_data_receive()). + * - USART_RDBF_FLAG can be also cleared by a read to the usart dt register(usart_data_receive()). + * - USART_TDC_FLAG can be also cleared by software sequence: a read operation to usart sts register (usart_flag_get()) + * followed by a write operation to usart dt register (usart_data_transmit()). + * - USART_TDBE_FLAG is cleared only by a write to the usart dt register(usart_data_transmit()). + * @retval none + */ +void usart_flag_clear(usart_type* usart_x, uint32_t flag) +{ + if(flag & (USART_PERR_FLAG | USART_FERR_FLAG | USART_NERR_FLAG | USART_ROERR_FLAG | USART_IDLEF_FLAG)) + { + UNUSED(usart_x->sts); + UNUSED(usart_x->dt); + } + else + { + usart_x->sts = ~flag; + } +} + +/** + * @brief configure the usart's rs485 transmit delay time. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param start_delay_time: transmit start delay time. + * @param complete_delay_time: transmit complete delay time. + * @retval none + */ +void usart_rs485_delay_time_config(usart_type* usart_x, uint8_t start_delay_time, uint8_t complete_delay_time) +{ + usart_x->ctrl1_bit.tsdt = start_delay_time; + usart_x->ctrl1_bit.tcdt = complete_delay_time; +} + +/** + * @brief swap the usart's transmit receive pin. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @param new_state: new state of the usart peripheral. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_transmit_receive_pin_swap(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.trpswap = new_state; +} + +/** + * @brief set the usart's identification bit num. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @param id_bit_num: the usart wakeup identification bit num. + * this parameter can be: USART_ID_FIXED_4_BIT or USART_ID_RELATED_DATA_BIT. + * @retval none + */ +void usart_id_bit_num_set(usart_type* usart_x, usart_identification_bit_num_type id_bit_num) +{ + usart_x->ctrl2_bit.idbn = (uint8_t)id_bit_num; +} + +/** + * @brief set the usart's de polarity. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param de_polarity: the usart de polarity selection. + * this parameter can be: USART_DE_POLARITY_HIGH or USART_DE_POLARITY_LOW. + * @retval none + */ +void usart_de_polarity_set(usart_type* usart_x, usart_de_polarity_type de_polarity) +{ + usart_x->ctrl3_bit.dep = (uint8_t)de_polarity; +} + +/** + * @brief enable or disable the usart's rs485 mode. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_rs485_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.rs485en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c new file mode 100644 index 0000000000..8c7afcbaa5 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c @@ -0,0 +1,1096 @@ +/** + ************************************************************************** + * @file at32f435_437_usb.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the usb firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup USB + * @brief USB driver modules + * @{ + */ + +#ifdef USB_MODULE_ENABLED + +/** @defgroup USB_private_functions + * @{ + */ + +#ifdef OTGFS_USB_GLOBAL +/** + * @brief usb global core soft reset + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval error status + */ +error_status usb_global_reset(otg_global_type *usbx) +{ + uint32_t timeout = 0; + while(usbx->grstctl_bit.ahbidle == RESET) + { + if(timeout ++ > 200000) + { + break; + } + } + timeout = 0; + usbx->grstctl_bit.csftrst = TRUE; + while(usbx->grstctl_bit.csftrst == SET) + { + if(timeout ++ > 200000) + { + break; + } + } + return SUCCESS; +} + +/** + * @brief usb global initialization + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_global_init(otg_global_type *usbx) +{ + /* reset otg moudle */ + usb_global_reset(usbx); + + /* exit power down mode */ + usbx->gccfg_bit.pwrdown = TRUE; +} + +/** + * @brief usb global select usb core (otg1 or otg2). + * @param usb_id: select otg1 or otg2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @retval usb global register type pointer + */ +otg_global_type *usb_global_select_core(uint8_t usb_id) +{ + if(usb_id == USB_OTG1_ID) + { + /* use otg1 */ + return OTG1_GLOBAL; + } + else + { + /* use otg2 */ + return OTG2_GLOBAL; + } +} + +/** + * @brief flush tx fifo + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param fifo_num: tx fifo num,when fifo_num=16,flush all tx fifo + * parameter as following values: 0-16 + * @retval none + */ +void usb_flush_tx_fifo(otg_global_type *usbx, uint32_t fifo_num) +{ + uint32_t timeout = 0; + /* set flush fifo number */ + usbx->grstctl_bit.txfnum = fifo_num; + + /* start flush fifo */ + usbx->grstctl_bit.txfflsh = TRUE; + + while(usbx->grstctl_bit.txfflsh == TRUE) + { + if(timeout ++ > 200000) + { + break; + } + } +} + +/** + * @brief flush rx fifo + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_flush_rx_fifo(otg_global_type *usbx) +{ + uint32_t timeout = 0; + usbx->grstctl_bit.rxfflsh = TRUE; + while(usbx->grstctl_bit.rxfflsh == TRUE) + { + if(timeout ++ > 200000) + { + break; + } + } +} + +/** + * @brief usb interrupt mask enable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param interrupt: + * this parameter can be any combination of the following values: + * - USB_OTG_MODEMIS_INT + * - USB_OTG_OTGINT_INT + * - USB_OTG_SOF_INT + * - USB_OTG_RXFLVL_INT + * - USB_OTG_NPTXFEMP_INT + * - USB_OTG_GINNAKEFF_INT + * - USB_OTG_GOUTNAKEFF_INT + * - USB_OTG_ERLYSUSP_INT + * - USB_OTG_USBSUSP_INT + * - USB_OTG_USBRST_INT + * - USB_OTG_ENUMDONE_INT + * - USB_OTG_ISOOUTDROP_INT + * - USB_OTG_IEPT_INT + * - USB_OTG_OEPT_INT + * - USB_OTG_INCOMISOIN_INT + * - USB_OTG_INCOMPIP_INCOMPISOOUT_INT + * - USB_OTG_PRT_INT + * - USB_OTG_HCH_INT + * - USB_OTG_PTXFEMP_INT + * - USB_OTG_CONIDSCHG_INT + * - USB_OTG_DISCON_INT + * - USB_OTG_WKUP_INT + * @param new_state: TRUE or FALSE + * @retval none + */ +void usb_global_interrupt_enable(otg_global_type *usbx, uint16_t interrupt, confirm_state new_state) +{ + if(new_state == TRUE) + { + usbx->gintmsk |= interrupt; + } + else + { + usbx->gintmsk &= ~interrupt; + } +} + +/** + * @brief get all global core interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval intterupt flag + */ +uint32_t usb_global_get_all_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = usbx->gintsts; + return intsts & usbx->gintmsk; +} + +/** + * @brief clear the global interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_MODEMIS_FLAG + * - USB_OTG_OTGINT_FLAG + * - USB_OTG_SOF_FLAG + * - USB_OTG_RXFLVL_FLAG + * - USB_OTG_NPTXFEMP_FLAG + * - USB_OTG_GINNAKEFF_FLAG + * - USB_OTG_GOUTNAKEFF_FLAG + * - USB_OTG_ERLYSUSP_FLAG + * - USB_OTG_USBSUSP_FLAG + * - USB_OTG_USBRST_FLAG + * - USB_OTG_ENUMDONE_FLAG + * - USB_OTG_ISOOUTDROP_FLAG + * - USB_OTG_EOPF_FLAG + * - USB_OTG_IEPT_FLAG + * - USB_OTG_OEPT_FLAG + * - USB_OTG_INCOMISOIN_FLAG + * - USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG + * - USB_OTG_PRT_FLAG + * - USB_OTG_HCH_FLAG + * - USB_OTG_PTXFEMP_FLAG + * - USB_OTG_CONIDSCHG_FLAG + * - USB_OTG_DISCON_FLAG + * - USB_OTG_WKUP_FLAG + * @retval none + */ +void usb_global_clear_interrupt(otg_global_type *usbx, uint32_t flag) +{ + usbx->gintsts = flag; +} + +/** + * @brief usb global interrupt enable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @retval none + */ +void usb_interrupt_enable(otg_global_type *usbx) +{ + usbx->gahbcfg_bit.glbintmsk = TRUE; +} + +/** + * @brief usb global interrupt disable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_interrupt_disable(otg_global_type *usbx) +{ + usbx->gahbcfg_bit.glbintmsk = FALSE; +} + +/** + * @brief usb set rx fifo size + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param size: rx fifo size + * @retval none + */ +void usb_set_rx_fifo(otg_global_type *usbx, uint16_t size) +{ + usbx->grxfsiz = size; +} + +/** + * @brief usb set tx fifo size + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param txfifo: the fifo number + * @param size: tx fifo size + * @retval none + */ +void usb_set_tx_fifo(otg_global_type *usbx, uint8_t txfifo, uint16_t size) +{ + uint8_t i_index = 0; + uint32_t offset = 0; + + offset = usbx->grxfsiz; + if(txfifo == 0) + { + usbx->gnptxfsiz_ept0tx = offset | (size << 16); + } + else + { + offset += usbx->gnptxfsiz_ept0tx_bit.nptxfdep; + for(i_index = 0; i_index < (txfifo - 1); i_index ++) + { + offset += usbx->dieptxfn_bit[i_index].ineptxfdep; + } + usbx->dieptxfn[txfifo - 1] = offset | (size << 16); + } +} + + +/** + * @brief set otg mode(device or host mode) + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param mode: + this parameter can be one of the following values: + * - OTG_DEVICE_MODE + * - OTG_HOST_MODE + * - OTG_DRD_MODE + * @retval none + */ +void usb_global_set_mode(otg_global_type *usbx, uint32_t mode) +{ + /* set otg to device mode */ + if(mode == OTG_DEVICE_MODE) + { + usbx->gusbcfg_bit.fhstmode = FALSE; + usbx->gusbcfg_bit.fdevmode = TRUE; + } + + /* set otg to host mode */ + if(mode == OTG_HOST_MODE) + { + usbx->gusbcfg_bit.fdevmode = FALSE; + usbx->gusbcfg_bit.fhstmode = TRUE; + } + + /* set otg to default mode */ + if(mode == OTG_DRD_MODE) + { + usbx->gusbcfg_bit.fdevmode = FALSE; + usbx->gusbcfg_bit.fhstmode = FALSE; + } +} + + +/** + * @brief disable the transceiver power down mode + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_global_power_on(otg_global_type *usbx) +{ + /* core soft reset */ + usbx->grstctl_bit.csftrst = TRUE; + while(usbx->grstctl_bit.csftrst); + + /* disable power down mode */ + usbx->gccfg_bit.pwrdown = TRUE; + +} + +/** + * @brief usb stop phy clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_stop_phy_clk(otg_global_type *usbx) +{ + OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = TRUE; +} + +/** + * @brief usb open phy clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_open_phy_clk(otg_global_type *usbx) +{ + OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = FALSE; +} + + +/** + * @brief write data from user memory to usb buffer + * @param pusr_buf: point to user buffer + * @param offset_addr: endpoint tx offset address + * @param nbytes: number of bytes data write to usb buffer + * @retval none + */ +void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes) +{ + uint32_t n_index; + uint32_t nhbytes = (nbytes + 3) / 4; + uint32_t *pbuf = (uint32_t *)pusr_buf; + for(n_index = 0; n_index < nhbytes; n_index ++) + { +#if defined (__ICCARM__) && (__VER__ < 7000000) + USB_FIFO(usbx, num) = *(__packed uint32_t *)pbuf; +#else + USB_FIFO(usbx, num) = __UNALIGNED_UINT32_READ(pbuf); +#endif + pbuf ++; + } +} + +/** + * @brief read data from usb buffer to user buffer + * @param pusr_buf: point to user buffer + * @param offset_addr: endpoint rx offset address + * @param nbytes: number of bytes data write to usb buffer + * @retval none + */ +void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes) +{ + UNUSED(num); + uint32_t n_index; + uint32_t nhbytes = (nbytes + 3) / 4; + uint32_t *pbuf = (uint32_t *)pusr_buf; + for(n_index = 0; n_index < nhbytes; n_index ++) + { +#if defined (__ICCARM__) && (__VER__ < 7000000) + *(__packed uint32_t *)pbuf = USB_FIFO(usbx, 0); +#else + __UNALIGNED_UINT32_WRITE(pbuf, (USB_FIFO(usbx, 0))); +#endif + pbuf ++; + } +} +#endif + + +#ifdef OTGFS_USB_DEVICE +/** + * @brief open usb endpoint + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_open(otg_global_type *usbx, usb_ept_info *ept_info) +{ + uint8_t mps = USB_EPT0_MPS_64; + if(ept_info->eptn == USB_EPT0) + { + if(ept_info->maxpacket == 0x40) + { + mps = USB_EPT0_MPS_64; + } + else if(ept_info->maxpacket == 0x20) + { + mps = USB_EPT0_MPS_32; + } + else if(ept_info->maxpacket == 0x10) + { + mps = USB_EPT0_MPS_16; + } + else if(ept_info->maxpacket == 0x08) + { + mps = USB_EPT0_MPS_8; + } + } + /* endpoint direction is in */ + if(ept_info->inout == EPT_DIR_IN) + { + OTG_DEVICE(usbx)->daintmsk |= 1 << ept_info->eptn; + if(ept_info->eptn == USB_EPT0) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = mps; + } + else + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = ept_info->maxpacket; + } + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptype = ept_info->trans_type; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.txfnum = ept_info->eptn; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = TRUE; + } + /* endpoint direction is out */ + else + { + OTG_DEVICE(usbx)->daintmsk |= (1 << ept_info->eptn) << 16; + if(ept_info->eptn == USB_EPT0) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = mps; + } + else + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = ept_info->maxpacket; + } + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptype = ept_info->trans_type; + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE; + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = TRUE; + } +} + +/** + * @brief close usb endpoint + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_close(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + OTG_DEVICE(usbx)->daintmsk &= ~(1 << ept_info->eptn); + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = FALSE; + } + else + { + OTG_DEVICE(usbx)->daintmsk &= ~((1 << ept_info->eptn) << 16); + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = FALSE; + } +} + + +/** + * @brief set endpoint tx or rx status to stall + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_stall(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + if(USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptena == RESET) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptdis = FALSE; + } + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = SET; + } + else + { + if(USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptena == RESET) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptdis = FALSE; + } + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = TRUE; + } +} + +/** + * @brief clear endpoint tx or rx status to stall + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_clear_stall(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = FALSE; + if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE; + } + } + else + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = FALSE; + if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE; + } + } +} + +/** + * @brief get all out endpoint interrupt bits + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval out endpoint interrupt bits + */ +uint32_t usb_get_all_out_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = OTG_DEVICE(usbx)->daint; + return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) >> 16); +} + +/** + * @brief get all in endpoint interrupt bits + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval in endpoint interrupt bits + */ +uint32_t usb_get_all_in_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = OTG_DEVICE(usbx)->daint; + return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) & 0xFFFF); +} + + +/** + * @brief get out endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval out endpoint interrupt flags + */ +uint32_t usb_ept_out_interrupt(otg_global_type *usbx, uint32_t eptn) +{ + uint32_t intsts = USB_OUTEPT(usbx, eptn)->doepint; + return (intsts & (OTG_DEVICE(usbx)->doepmsk)); +} + +/** + * @brief get in endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval in endpoint intterupt flags + */ +uint32_t usb_ept_in_interrupt(otg_global_type *usbx, uint32_t eptn) +{ + uint32_t intsts, mask1, mask2; + mask1 = OTG_DEVICE(usbx)->diepmsk; + mask2 = OTG_DEVICE(usbx)->diepempmsk; + mask1 |= ((mask2 >> eptn) & 0x1) << 7; + intsts = USB_INEPT(usbx, eptn)->diepint & mask1; + return intsts; +} + +/** + * @brief clear out endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_DOEPINT_XFERC_FLAG + * - USB_OTG_DOEPINT_EPTDISD_FLAG + * - USB_OTG_DOEPINT_SETUP_FLAG + * - USB_OTG_DOEPINT_OTEPDIS_FLAG + * - USB_OTG_DOEPINT_B2BSTUP_FLAG + */ +void usb_ept_out_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag) +{ + USB_OUTEPT(usbx, eptn)->doepint = flag; +} + +/** + * @brief clear in endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_DIEPINT_XFERC_FLAG + * - USB_OTG_DIEPINT_EPTDISD_FLAG + * - USB_OTG_DIEPINT_TMROC_FLAG + * - USB_OTG_DIEPINT_INTTXFE_FLAG + * - USB_OTG_DIEPINT_INEPNE_FLAG + * - USB_OTG_DIEPINT_TXFE_FLAG + */ +void usb_ept_in_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag) +{ + USB_INEPT(usbx, eptn)->diepint = flag; +} + + +/** + * @brief set the host assignment address + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param address: host assignment address + * @retval none + */ +void usb_set_address(otg_global_type *usbx, uint8_t address) +{ + OTG_DEVICE(usbx)->dcfg_bit.devaddr = address; +} + +/** + * @brief enable endpoint 0 out + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_ept0_start(otg_global_type *usbx) +{ + otg_eptout_type *usb_outept = USB_OUTEPT(usbx, 0); + usb_outept->doeptsiz = 0; + usb_outept->doeptsiz_bit.pktcnt = 1; + usb_outept->doeptsiz_bit.xfersize = 24; + usb_outept->doeptsiz_bit.rxdpid_setupcnt = 3; +} + + +/** + * @brief endpoint 0 start setup + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_ept0_setup(otg_global_type *usbx) +{ + USB_INEPT(usbx, 0)->diepctl_bit.mps = 0; + OTG_DEVICE(usbx)->dctl_bit.cgnpinak = FALSE; +} + +/** + * @brief connect usb device by enable pull-up + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_connect(otg_global_type *usbx) +{ + /* D+ 1.5k pull-up enable */ + OTG_DEVICE(usbx)->dctl_bit.sftdiscon = FALSE; +} + +/** + * @brief disconnect usb device by disable pull-up + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_disconnect(otg_global_type *usbx) +{ + /* D+ 1.5k pull-up disable */ + OTG_DEVICE(usbx)->dctl_bit.sftdiscon = TRUE; +} + + +/** + * @brief usb remote wakeup set + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_remote_wkup_set(otg_global_type *usbx) +{ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = TRUE; +} + +/** + * @brief usb remote wakeup clear + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_remote_wkup_clear(otg_global_type *usbx) +{ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE; +} + +/** + * @brief usb suspend status get + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval usb suspend status + */ +uint8_t usb_suspend_status_get(otg_global_type *usbx) +{ + return OTG_DEVICE(usbx)->dsts_bit.suspsts; +} +#endif + +#ifdef OTGFS_USB_HOST +/** + * @brief usb port power on + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param state: state (TRUE or FALSE) + * @retval none + */ +void usb_port_power_on(otg_global_type *usbx, confirm_state state) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + uint32_t hprt_val = usb_host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + if(state == TRUE) + { + usb_host->hprt = hprt_val | USB_OTG_HPRT_PRTPWR; + } + else + { + usb_host->hprt = hprt_val & (~USB_OTG_HPRT_PRTPWR); + } +} + +/** + * @brief get current frame number + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +uint32_t usbh_get_frame(otg_global_type *usbx) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + return usb_host->hfnum & 0xFFFF; +} + +/** + * @brief enable one host channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: host channel number + * @param ept_num: devvice endpoint number + * @param dev_address: device address + * @param type: channel transfer type + * this parameter can be one of the following values: + * - EPT_CONTROL_TYPE + * - EPT_BULK_TYPE + * - EPT_INT_TYPE + * - EPT_ISO_TYPE + * @param maxpacket: support max packe size for this channel + * @param speed: device speed + * this parameter can be one of the following values: + * - USB_PRTSPD_FULL_SPEED + * - USB_PRTSPD_LOW_SPEED + * @retval none + */ +void usb_hc_enable(otg_global_type *usbx, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed) +{ + otg_hchannel_type *hch = USB_CHL(usbx, chn); + otg_host_type *usb_host = OTG_HOST(usbx); + + switch(type) + { + case EPT_CONTROL_TYPE: + case EPT_BULK_TYPE: + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT | + USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT | + USB_OTG_HC_DTGLERRM_INT; + if(ept_num & 0x80) + { + hch->hcintmsk_bit.bblerrmsk = TRUE; + } + break; + case EPT_INT_TYPE: + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT | + USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT | + USB_OTG_HC_DTGLERRM_INT | USB_OTG_HC_FRMOVRRUN_INT; + break; + case EPT_ISO_TYPE: + + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_ACKM_INT | + USB_OTG_HC_FRMOVRRUN_INT; + break; + } + usb_host->haintmsk |= 1 << chn; + usbx->gintmsk_bit.hchintmsk = TRUE; + + hch->hcchar_bit.devaddr = dev_address; + hch->hcchar_bit.eptnum = ept_num & 0x7F; + hch->hcchar_bit.eptdir = (ept_num & 0x80)?1:0; + hch->hcchar_bit.lspddev = (speed == USB_PRTSPD_LOW_SPEED)?1:0; + hch->hcchar_bit.eptype = type; + hch->hcchar_bit.mps = maxpacket; + + if(type == EPT_INT_TYPE) + { + hch->hcchar_bit.oddfrm = TRUE; + } +} + +/** + * @brief host read channel interrupt + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval interrupt flag + */ +uint32_t usb_hch_read_interrupt(otg_global_type *usbx) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + return usb_host->haint & 0xFFFF; +} + +/** + * @brief disable host + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_host_disable(otg_global_type *usbx) +{ + uint32_t i_index = 0, count = 0; + otg_hchannel_type *hch; + otg_host_type *usb_host = OTG_HOST(usbx); + + usbx->gahbcfg_bit.glbintmsk = FALSE; + usb_flush_rx_fifo(usbx); + usb_flush_tx_fifo(usbx, 0x10); + + for(i_index = 0; i_index < 16; i_index ++) + { + hch = USB_CHL(usbx, i_index); + hch->hcchar_bit.chdis = TRUE; + hch->hcchar_bit.chena = FALSE; + hch->hcchar_bit.eptdir = 0; + } + + for(i_index = 0; i_index < 16; i_index ++) + { + hch = USB_CHL(usbx, i_index); + hch->hcchar_bit.chdis = TRUE; + hch->hcchar_bit.chena = TRUE; + hch->hcchar_bit.eptdir = 0; + do + { + if(count ++ > 1000) + break; + }while(hch->hcchar_bit.chena); + } + usb_host->haint = 0xFFFFFFFF; + usbx->gintsts = 0xFFFFFFFF; + usbx->gahbcfg_bit.glbintmsk = TRUE; +} + +/** + * @brief halt channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: channel number + * @retval none + */ +void usb_hch_halt(otg_global_type *usbx, uint8_t chn) +{ + uint32_t count = 0; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + otg_host_type *usb_host = OTG_HOST(usbx); + + /* endpoint type is control or bulk */ + if(usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE || + usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE) + { + usb_chh->hcchar_bit.chdis = TRUE; + if((usbx->gnptxsts_bit.nptxqspcavail) == 0) + { + usb_chh->hcchar_bit.chena = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + do + { + if(count ++ > 1000) + break; + }while(usb_chh->hcchar_bit.chena == SET); + } + else + { + usb_chh->hcchar_bit.chena = TRUE; + } + } + else + { + usb_chh->hcchar_bit.chdis = TRUE; + if((usb_host->hptxsts_bit.ptxqspcavil) == 0) + { + usb_chh->hcchar_bit.chena = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + do + { + if(count ++ > 1000) + break; + }while(usb_chh->hcchar_bit.chena == SET); + } + else + { + usb_chh->hcchar_bit.chena = TRUE; + } + } +} +/** + * @brief select full or low speed clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param clk: clock frequency + * @retval none + */ +void usbh_fsls_clksel(otg_global_type *usbx, uint8_t clk) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + + usb_host->hcfg_bit.fslspclksel = clk; + if(clk == USB_HCFG_CLK_6M) + { + usb_host->hfir = 6000; + } + else + { + usb_host->hfir = 48000; + } +} +#endif + + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c new file mode 100644 index 0000000000..e159ed604c --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c @@ -0,0 +1,156 @@ +/** + ************************************************************************** + * @file at32f435_437_wdt.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the wdt firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup WDT + * @brief WDT driver modules + * @{ + */ + +#ifdef WDT_MODULE_ENABLED + +/** @defgroup WDT_private_functions + * @{ + */ + +/** + * @brief wdt enable ,the reload value will be sent to the counter + * @param none + * @retval none + */ +void wdt_enable(void) +{ + WDT->cmd = WDT_CMD_ENABLE; +} + +/** + * @brief reload wdt counter + * @param none + * @retval none + */ +void wdt_counter_reload(void) +{ + WDT->cmd = WDT_CMD_RELOAD; +} + +/** + * @brief set wdt counter reload value + * @param reload_value (0x0000~0x0FFF) + * @retval none + */ +void wdt_reload_value_set(uint16_t reload_value) +{ + WDT->rld = reload_value; +} + +/** + * @brief set wdt division divider + * @param division + * this parameter can be one of the following values: + * - WDT_CLK_DIV_4 + * - WDT_CLK_DIV_8 + * - WDT_CLK_DIV_16 + * - WDT_CLK_DIV_32 + * - WDT_CLK_DIV_64 + * - WDT_CLK_DIV_128 + * - WDT_CLK_DIV_256 + * @retval none + */ +void wdt_divider_set(wdt_division_type division) +{ + WDT->div_bit.div = division; +} + +/** + * @brief enable or disable wdt cmd register write + * @param new_state (TRUE or FALSE) + * @retval none + */ +void wdt_register_write_enable( confirm_state new_state) +{ + if(new_state == FALSE) + { + WDT->cmd = WDT_CMD_LOCK; + } + else + { + WDT->cmd = WDT_CMD_UNLOCK; + } +} + +/** + * @brief get wdt flag + * @param wdt_flag + * this parameter can be one of the following values: + * - WDT_DIVF_UPDATE_FLAG: division value update complete flag. + * - WDT_RLDF_UPDATE_FLAG: reload value update complete flag. + * - WDT_WINF_UPDATE_FLAG: window value update complete flag. + * @retval state of wdt flag + */ +flag_status wdt_flag_get(uint16_t wdt_flag) +{ + flag_status status = RESET; + + if ((WDT->sts & wdt_flag) != (uint16_t)RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief wdt window counter value set + * @param window_cnt (0x0000~0x0FFF) + * @retval none + */ +void wdt_window_counter_set(uint16_t window_cnt) +{ + WDT->win_bit.win = window_cnt; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c new file mode 100644 index 0000000000..4f03e650ce --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c @@ -0,0 +1,141 @@ +/** + ************************************************************************** + * @file at32f435_437_wwdt.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the wwdt firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup WWDT + * @brief WWDT driver modules + * @{ + */ + +#ifdef WWDT_MODULE_ENABLED + +/** @defgroup WWDT_private_functions + * @{ + */ + +/** + * @brief wwdt reset by crm reset register + * @retval none + */ +void wwdt_reset(void) +{ + crm_periph_reset(CRM_WWDT_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_WWDT_PERIPH_RESET, FALSE); +} + +/** + * @brief wwdt division set + * @param division + * this parameter can be one of the following values: + * - WWDT_PCLK1_DIV_4096 (wwdt counter clock = (pclk1/4096)/1) + * - WWDT_PCLK1_DIV_8192 (wwdt counter clock = (pclk1/4096)/2) + * - WWDT_PCLK1_DIV_16384 (wwdt counter clock = (pclk1/4096)/4) + * - WWDT_PCLK1_DIV_32768 (wwdt counter clock = (pclk1/4096)/8) + * @retval none + */ +void wwdt_divider_set(wwdt_division_type division) +{ + WWDT->cfg_bit.div = division; +} + +/** + * @brief wwdt reload counter interrupt flag clear + * @param none + * @retval none + */ +void wwdt_flag_clear(void) +{ + WWDT->sts = 0; +} + +/** + * @brief wwdt enable and the counter value load + * @param wwdt_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_enable(uint8_t wwdt_cnt) +{ + WWDT->ctrl = wwdt_cnt | WWDT_EN_BIT; +} + +/** + * @brief wwdt reload counter interrupt enable + * @param none + * @retval none + */ +void wwdt_interrupt_enable(void) +{ + WWDT->cfg_bit.rldien = TRUE; +} + +/** + * @brief wwdt reload counter interrupt flag get + * @param none + * @retval state of reload counter interrupt flag + */ +flag_status wwdt_flag_get(void) +{ + return (flag_status)WWDT->sts_bit.rldf; +} + +/** + * @brief wwdt counter value set + * @param wwdt_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_counter_set(uint8_t wwdt_cnt) +{ + WWDT->ctrl_bit.cnt = wwdt_cnt; +} + +/** + * @brief wwdt window counter value set + * @param window_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_window_counter_set(uint8_t window_cnt) +{ + WWDT->cfg_bit.win = window_cnt; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c new file mode 100644 index 0000000000..7cb2768320 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c @@ -0,0 +1,909 @@ +/** + ************************************************************************** + * @file at32f435_437_xmc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the xmc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup XMC + * @brief XMC driver modules + * @{ + */ + +#ifdef XMC_MODULE_ENABLED + +/** @defgroup XMC_private_functions + * @{ + */ + +/** + * @brief xmc nor or sram registers reset + * @param xmc_subbank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @retval none + */ +void xmc_nor_sram_reset(xmc_nor_sram_subbank_type xmc_subbank) +{ + /* XMC_BANK1_NORSRAM1 */ + if(xmc_subbank == XMC_BANK1_NOR_SRAM1) + { + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl = 0x000030DB; + } + /* XMC_BANK1_NORSRAM2, XMC_BANK1_NORSRAM3 or XMC_BANK1_NORSRAM4 */ + else + { + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl = 0x000030D2; + } + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1tmg = 0x0FFFFFFF; + XMC_BANK1->tmgwr_group[xmc_subbank].bk1tmgwr = 0x0FFFFFFF; +} + +/** + * @brief initialize the xmc nor/sram banks according to the specified + * parameters in the xmc_norsraminitstruct. + * @param xmc_norsram_init_struct : pointer to a xmc_norsram_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @retval none + */ +void xmc_nor_sram_init(xmc_norsram_init_type* xmc_norsram_init_struct) +{ + /* bank1 nor/sram control register configuration */ + XMC_BANK1->ctrl_tmg_group[xmc_norsram_init_struct->subbank].bk1ctrl = + (uint32_t)xmc_norsram_init_struct->data_addr_multiplex | + xmc_norsram_init_struct->device | + xmc_norsram_init_struct->bus_type | + xmc_norsram_init_struct->burst_mode_enable | + xmc_norsram_init_struct->asynwait_enable | + xmc_norsram_init_struct->wait_signal_lv | + xmc_norsram_init_struct->wrapped_mode_enable | + xmc_norsram_init_struct->wait_signal_config | + xmc_norsram_init_struct->write_enable | + xmc_norsram_init_struct->wait_signal_enable | + xmc_norsram_init_struct->write_timing_enable | + xmc_norsram_init_struct->write_burst_syn; + + /* if nor flash device */ + if(xmc_norsram_init_struct->device == XMC_DEVICE_NOR) + { + XMC_BANK1->ctrl_tmg_group[xmc_norsram_init_struct->subbank].bk1ctrl_bit.noren = 0x1; + } +} + +/** + * @brief initialize the xmc nor/sram banks according to the specified + * parameters in the xmc_rw_timing_struct and xmc_w_timing_struct. + * @param xmc_rw_timing_struct : pointer to a xmc_norsram_timing_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @param xmc_w_timing_struct : pointer to a xmc_norsram_timing_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @retval none + */ +void xmc_nor_sram_timing_config(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct) +{ + /* bank1 nor/sram timing register configuration */ + XMC_BANK1->ctrl_tmg_group[xmc_rw_timing_struct->subbank].bk1tmg = + (uint32_t)xmc_rw_timing_struct->addr_setup_time | + (xmc_rw_timing_struct->addr_hold_time << 4) | + (xmc_rw_timing_struct->data_setup_time << 8) | + (xmc_rw_timing_struct->bus_latency_time <<16) | + (xmc_rw_timing_struct->clk_psc << 20) | + (xmc_rw_timing_struct->data_latency_time << 24) | + xmc_rw_timing_struct->mode; + + /* bank1 nor/sram timing register for write configuration, if extended mode is used */ + if(xmc_rw_timing_struct->write_timing_enable == XMC_WRITE_TIMING_ENABLE) + { + XMC_BANK1->tmgwr_group[xmc_w_timing_struct->subbank].bk1tmgwr = + (uint32_t)xmc_w_timing_struct->addr_setup_time | + (xmc_w_timing_struct->addr_hold_time << 4) | + (xmc_w_timing_struct->data_setup_time << 8) | + (xmc_w_timing_struct->bus_latency_time << 16) | + (xmc_w_timing_struct->clk_psc << 20) | + (xmc_w_timing_struct->data_latency_time << 24) | + xmc_w_timing_struct->mode; + } + else + { + XMC_BANK1->tmgwr_group[xmc_w_timing_struct->subbank].bk1tmgwr = 0x0FFFFFFF; + } +} + +/** + * @brief fill each xmc_nor_sram_init_struct member with its default value. + * @param xmc_nor_sram_init_struct: pointer to a xmc_norsram_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_norsram_default_para_init(xmc_norsram_init_type* xmc_nor_sram_init_struct) +{ + /* reset nor/sram init structure parameters values */ + xmc_nor_sram_init_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_nor_sram_init_struct->data_addr_multiplex = XMC_DATA_ADDR_MUX_ENABLE; + xmc_nor_sram_init_struct->device = XMC_DEVICE_SRAM; + xmc_nor_sram_init_struct->bus_type = XMC_BUSTYPE_8_BITS; + xmc_nor_sram_init_struct->burst_mode_enable = XMC_BURST_MODE_DISABLE; + xmc_nor_sram_init_struct->asynwait_enable = XMC_ASYN_WAIT_DISABLE; + xmc_nor_sram_init_struct->wait_signal_lv = XMC_WAIT_SIGNAL_LEVEL_LOW; + xmc_nor_sram_init_struct->wrapped_mode_enable = XMC_WRAPPED_MODE_DISABLE; + xmc_nor_sram_init_struct->wait_signal_config = XMC_WAIT_SIGNAL_SYN_BEFORE; + xmc_nor_sram_init_struct->write_enable = XMC_WRITE_OPERATION_ENABLE; + xmc_nor_sram_init_struct->wait_signal_enable = XMC_WAIT_SIGNAL_ENABLE; + xmc_nor_sram_init_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_nor_sram_init_struct->write_burst_syn = XMC_WRITE_BURST_SYN_DISABLE; +} + +/** + * @brief fill each xmc_rw_timing_struct and xmc_w_timing_struct member with its default value. + * @param xmc_rw_timing_struct: pointer to a xmc_norsram_timing_init_type + * structure which will be initialized. + * @param xmc_w_timing_struct: pointer to a xmc_norsram_timing_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_norsram_timing_default_para_init(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct) +{ + xmc_rw_timing_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_rw_timing_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_rw_timing_struct->addr_setup_time = 0xF; + xmc_rw_timing_struct->addr_hold_time = 0xF; + xmc_rw_timing_struct->data_setup_time = 0xFF; + xmc_rw_timing_struct->bus_latency_time = 0xF; + xmc_rw_timing_struct->clk_psc = 0xF; + xmc_rw_timing_struct->data_latency_time = 0xF; + xmc_rw_timing_struct->mode = XMC_ACCESS_MODE_A; + xmc_w_timing_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_w_timing_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_w_timing_struct->addr_setup_time = 0xF; + xmc_w_timing_struct->addr_hold_time = 0xF; + xmc_w_timing_struct->data_setup_time = 0xFF; + xmc_w_timing_struct->bus_latency_time = 0xF; + xmc_w_timing_struct->clk_psc = 0xF; + xmc_w_timing_struct->data_latency_time = 0xF; + xmc_w_timing_struct->mode = XMC_ACCESS_MODE_A; +} + +/** + * @brief enable or disable the specified nor/sram memory bank. + * @param xmc_subbank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nor_sram_enable(xmc_nor_sram_subbank_type xmc_subbank, confirm_state new_state) +{ + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl_bit.en = new_state; +} + +/** + * @brief config the bus turnaround phase. + * @param xmc_sub_bank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @param w2w_timing :write timing + * @param r2r_timing :read timing + * @retval none + */ +void xmc_ext_timing_config(xmc_nor_sram_subbank_type xmc_sub_bank, uint16_t w2w_timing, uint16_t r2r_timing) +{ + XMC_BANK1->ext_bit[xmc_sub_bank].buslatr2r = r2r_timing<<8; + XMC_BANK1->ext_bit[xmc_sub_bank].buslatw2w = w2w_timing; +} + +/** + * @brief xmc nand flash registers reset + * @param xmc_bank + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @retval none + */ +void xmc_nand_reset(xmc_class_bank_type xmc_bank) +{ + /* set the xmc_bank2_nand registers to their reset values */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl = 0x00000018; + XMC_BANK2->bk2is = 0x00000040; + XMC_BANK2->bk2tmgatt = 0xFCFCFCFC; + XMC_BANK2->bk2tmgmem = 0xFCFCFCFC; + } + /* set the xmc_bank3_nand registers to their reset values */ + else + { + XMC_BANK3->bk3ctrl = 0x00000018; + XMC_BANK3->bk3is = 0x00000040; + XMC_BANK3->bk3tmgatt = 0xFCFCFCFC; + XMC_BANK3->bk3tmgmem = 0xFCFCFCFC; + } +} + +/** + * @brief initialize the xmc nand banks according to the specified + * parameters in the xmc_nandinitstruct. + * @param xmc_nand_init_struct : pointer to a xmc_nand_init_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @retval none + */ +void xmc_nand_init(xmc_nand_init_type* xmc_nand_init_struct) +{ + uint32_t tempctrl = 0x0; + + /* Set the tempctrl value according to xmc_nand_init_struct parameters */ + tempctrl = (uint32_t)xmc_nand_init_struct->wait_enable | + xmc_nand_init_struct->bus_type | + xmc_nand_init_struct->ecc_enable | + xmc_nand_init_struct->ecc_pagesize | + (xmc_nand_init_struct->delay_time_cycle << 9) | + (xmc_nand_init_struct->delay_time_ar << 13) | + 0x00000008; + + /* xmc_bank2_nand registers configuration */ + if(xmc_nand_init_struct->nand_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl = tempctrl; + } + /* xmc_bank3_nand registers configuration */ + else + { + XMC_BANK3->bk3ctrl = tempctrl; + } +} + +/** + * @brief initialize the xmc nand banks according to the specified + * parameters in the xmc_nandinitstruct. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_nand_pccard_timinginit_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @param xmc_special_spacetiming_struct : pointer to a xmc_nand_pccard_timinginit_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @retval none + */ +void xmc_nand_timing_config(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct) +{ + uint32_t tempmem = 0x0, tempatt = 0x0; + + /* set the tempmem value according to xmc_nand_init_struct parameters */ + tempmem = (uint32_t)xmc_regular_spacetiming_struct->mem_setup_time | + (xmc_regular_spacetiming_struct->mem_waite_time << 8) | + (xmc_regular_spacetiming_struct->mem_hold_time << 16) | + (xmc_regular_spacetiming_struct->mem_hiz_time << 24); + + /* set the tempatt value according to xmc_nand_init_struct parameters */ + tempatt = (uint32_t)xmc_special_spacetiming_struct->mem_setup_time | + (xmc_special_spacetiming_struct->mem_waite_time << 8) | + (xmc_special_spacetiming_struct->mem_hold_time << 16) | + (xmc_special_spacetiming_struct->mem_hiz_time << 24); + /* xmc_bank2_nand registers configuration */ + if(xmc_regular_spacetiming_struct->class_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2tmgatt = tempatt; + XMC_BANK2->bk2tmgmem = tempmem; + } + else + { + XMC_BANK3->bk3tmgatt = tempatt; + XMC_BANK3->bk3tmgmem = tempmem; + } +} + +/** + * @brief fill each xmc_nand_init_struct member with its default value. + * @param xmc_nand_init_struct: pointer to a xmc_nand_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_nand_default_para_init(xmc_nand_init_type* xmc_nand_init_struct) +{ + /* reset nand init structure parameters values */ + xmc_nand_init_struct->nand_bank = XMC_BANK2_NAND; + xmc_nand_init_struct->wait_enable = XMC_WAIT_OPERATION_DISABLE; + xmc_nand_init_struct->bus_type = XMC_BUSTYPE_8_BITS; + xmc_nand_init_struct->ecc_enable = XMC_ECC_OPERATION_DISABLE; + xmc_nand_init_struct->ecc_pagesize = XMC_ECC_PAGESIZE_256_BYTES; + xmc_nand_init_struct->delay_time_cycle = 0x0; + xmc_nand_init_struct->delay_time_ar = 0x0; +} + +/** + * @brief fill each xmc_common_spacetiming_struct and xmc_attribute_spacetiming_struct member with its default value. + * @param xmc_common_spacetiming_struct: pointer to a xmc_nand_pccard_timinginit_type + * structure which will be initialized. + * @param xmc_special_spacetiming_struct: pointer to a xmc_nand_pccard_timinginit_type + * structure which will be initialized. + * @retval none + */ +void xmc_nand_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct) +{ + xmc_regular_spacetiming_struct->class_bank = XMC_BANK2_NAND; + xmc_regular_spacetiming_struct->mem_hold_time = 0xFC; + xmc_regular_spacetiming_struct->mem_waite_time = 0xFC; + xmc_regular_spacetiming_struct->mem_setup_time = 0xFC; + xmc_regular_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_special_spacetiming_struct->class_bank = XMC_BANK2_NAND; + xmc_special_spacetiming_struct->mem_hold_time = 0xFC; + xmc_special_spacetiming_struct->mem_waite_time = 0xFC; + xmc_special_spacetiming_struct->mem_setup_time = 0xFC; + xmc_special_spacetiming_struct->mem_hiz_time = 0xFC; +} + +/** + * @brief enable or disable the specified nand memory bank. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nand_enable(xmc_class_bank_type xmc_bank, confirm_state new_state) +{ + /* enable or disable the nand bank2 by setting the en bit in the bk2ctrl register */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl_bit.en = new_state; + } + /* enable or disable the nand bank3 by setting the en bit in the bk3ctrl register */ + else + { + XMC_BANK3->bk3ctrl_bit.en = new_state; + } +} + +/** + * @brief enable or disable the xmc nand ecc feature. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nand_ecc_enable(xmc_class_bank_type xmc_bank, confirm_state new_state) +{ + /* enable the selected nand bank2 ecc function by setting the eccen bit in the bk2ctrl register */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl_bit.eccen = new_state; + } + /* enable the selected nand bank3 ecc function by setting the eccen bit in the bk3ctrl register */ + else + { + XMC_BANK3->bk3ctrl_bit.eccen = new_state; + } +} + +/** + * @brief return the error correction code register value. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @retval the error correction code (ecc) value. + */ +uint32_t xmc_ecc_get(xmc_class_bank_type xmc_bank) +{ + uint32_t eccvaule = 0x0; + + /* get the bk2ecc register value */ + if(xmc_bank == XMC_BANK2_NAND) + { + eccvaule = XMC_BANK2->bk2ecc; + } + /* get the bk3ecc register value */ + else + { + eccvaule = XMC_BANK3->bk3ecc; + } + /* return the error correction code value */ + return eccvaule; +} + +/** + * @brief xmc sdram registers reset + * @param xmc_bank + * this parameter can be one of the following values: + * - XMC_SDRAM_BANK1 + * - XMC_SDRAM_BANK2 + * @retval none + */ +void xmc_sdram_reset(xmc_sdram_bank_type xmc_bank) +{ + XMC_SDRAM->ctrl[xmc_bank] = 0x000002D0; + XMC_SDRAM->tm[xmc_bank] = 0x0FFFFFFF; + XMC_SDRAM->cmd = 0x00000000; + XMC_SDRAM->rcnt = 0x00000000; + XMC_SDRAM->sts = 0x00000000; +} + +/** + * @brief initialize the xmc sdram banks according to the specified + * parameters in the xmc_sdram_init_struct and xmc_sdram_timing_struct. + * @param xmc_sdram_init_struct : pointer to a xmc_sdram_init_type + * structure that contains the configuration information for the xmc + * sdram specified banks. + * @param xmc_sdram_timing_struct : pointer to a xmc_sdram_timing_type + * structure that contains the configuration information for the xmc + * sdram specified banks. + * @retval none + */ +void xmc_sdram_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct) +{ + if(xmc_sdram_init_struct->sdram_bank == XMC_SDRAM_BANK1) + { + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].ca = xmc_sdram_init_struct->column_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].ra = xmc_sdram_init_struct->row_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].db = xmc_sdram_init_struct->width; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].inbk = xmc_sdram_init_struct->internel_banks; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].cas = xmc_sdram_init_struct->cas; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].wrp = xmc_sdram_init_struct->write_protection; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].bstr = xmc_sdram_init_struct->burst_read; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].rd = xmc_sdram_init_struct->read_delay; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].clkdiv = xmc_sdram_init_struct->clkdiv; + + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].tmrd = xmc_sdram_timing_struct->tmrd; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].txsr = xmc_sdram_timing_struct->txsr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].tras = xmc_sdram_timing_struct->tras; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trc = xmc_sdram_timing_struct->trc; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].twr = xmc_sdram_timing_struct->twr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trp = xmc_sdram_timing_struct->trp; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trcd = xmc_sdram_timing_struct->trcd; + } + + if(xmc_sdram_init_struct->sdram_bank == XMC_SDRAM_BANK2) + { + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].ca = xmc_sdram_init_struct->column_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].ra = xmc_sdram_init_struct->row_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].db = xmc_sdram_init_struct->width; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].inbk = xmc_sdram_init_struct->internel_banks; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].cas = xmc_sdram_init_struct->cas; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].wrp = xmc_sdram_init_struct->write_protection; + /* sdctrl2 bstr is not care */ + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].bstr = xmc_sdram_init_struct->burst_read; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].rd = xmc_sdram_init_struct->read_delay; + /* sdctrl2 clkdiv is not care */ + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].clkdiv = xmc_sdram_init_struct->clkdiv; + + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].tmrd = xmc_sdram_timing_struct->tmrd; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].txsr = xmc_sdram_timing_struct->txsr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].tras = xmc_sdram_timing_struct->tras; + /* sdtm2 trc is not care */ + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trc = xmc_sdram_timing_struct->trc; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].twr = xmc_sdram_timing_struct->twr; + /* sdtm2 trp is not care */ + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trp = xmc_sdram_timing_struct->trp; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].trcd = xmc_sdram_timing_struct->trcd; + } +} + +/** + * @brief fill each xmc_sdram_init_struct member with its default value. + * @param xmc_sdram_init_struct: pointer to a xmc_sdram_init_type + * structure which will be initialized. + * @param xmc_sdram_timing_struct: pointer to a xmc_sdram_timing_type + * structure which will be initialized. + * @retval none + */ +void xmc_sdram_default_para_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct) +{ + /* reset sdram init structure parameters values */ + xmc_sdram_init_struct->sdram_bank = XMC_SDRAM_BANK1; + xmc_sdram_init_struct->internel_banks = XMC_INBK_4; + xmc_sdram_init_struct->clkdiv = XMC_NO_CLK; + xmc_sdram_init_struct->write_protection = FALSE; + xmc_sdram_init_struct->burst_read = FALSE; + xmc_sdram_init_struct->column_address = XMC_COLUMN_8; + xmc_sdram_init_struct->row_address = XMC_ROW_11; + xmc_sdram_init_struct->cas = XMC_CAS_1; + xmc_sdram_init_struct->width = XMC_MEM_WIDTH_8; + xmc_sdram_init_struct->read_delay = XMC_READ_DELAY_1; + + xmc_sdram_timing_struct->tmrd = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->txsr = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->tras = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trc = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->twr = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trp = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trcd = XMC_DELAY_CYCLE_16; +} + +/** + * @brief sdram command confg + * @param xmc_sdram_cmd_struct: pointer to a xmc_sdram_cmd_type + * structure which will be initialized. + * @retval none + */ +void xmc_sdram_cmd(xmc_sdram_cmd_type *xmc_sdram_cmd_struct) +{ + XMC_SDRAM->cmd = (xmc_sdram_cmd_struct->auto_refresh << 5) | + (xmc_sdram_cmd_struct->data << 9) | + xmc_sdram_cmd_struct->cmd | + xmc_sdram_cmd_struct->cmd_banks; +} + + +/** + * @brief get sdram bank status + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_SDRAM_BANK1 + * - XMC_SDRAM_BANK1 + * @retval the bank status + */ +uint32_t xmc_sdram_status_get(xmc_sdram_bank_type xmc_bank) +{ + if(xmc_bank == XMC_SDRAM_BANK1) + { + return ((XMC_SDRAM->sts >> 1) & XMC_STATUS_MASK); + } + else + { + return ((XMC_SDRAM->sts >> 3) & XMC_STATUS_MASK); + } +} + +/** + * @brief set sdram refresh counter + * @param counter: xmc sdram refresh counter + * @retval none + */ +void xmc_sdram_refresh_counter_set(uint32_t counter) +{ + XMC_SDRAM->rcnt_bit.rc = counter; +} + +/** + * @brief set sdram auto refresh number + * @param number: xmc sdram auto refresh number + * @retval none + */ +void xmc_sdram_auto_refresh_set(uint32_t number) +{ + XMC_SDRAM->cmd_bit.art = number; +} + +/** + * @brief enable or disable the specified xmc interrupts. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_int: specifies the xmc interrupt sources to be enabled or disabled. + * this parameter can be any combination of the following values: + * - XMC_INT_RISING_EDGE + * - XMC_INT_LEVEL + * - XMC_INT_FALLING_EDGE + * - XMC_INT_ERR + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_interrupt_enable(xmc_class_bank_type xmc_bank, xmc_interrupt_sources_type xmc_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + /* enable the selected xmc_bank2 interrupts */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2is |= xmc_int; + } + /* enable the selected xmc_bank3 interrupts */ + else if(xmc_bank == XMC_BANK3_NAND) + { + XMC_BANK3->bk3is |= xmc_int; + } + /* enable the selected xmc_bank4 interrupts */ + else if(xmc_bank == XMC_BANK4_PCCARD) + { + XMC_BANK4->bk4is |= xmc_int; + } + /* enable the selected xmc_sdram interrupts */ + else + { + XMC_SDRAM->rcnt |= xmc_int; + } + } + else + { + /* disable the selected xmc_bank2 interrupts */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2is &= ~xmc_int; + } + /* disable the selected xmc_bank3 interrupts */ + else if(xmc_bank == XMC_BANK3_NAND) + { + XMC_BANK3->bk3is &= ~xmc_int; + } + /* disable the selected xmc_bank4 interrupts */ + else if(xmc_bank == XMC_BANK4_PCCARD) + { + XMC_BANK4->bk4is &= ~xmc_int; + } + /* disable the selected xmc_sdram interrupts */ + else + { + XMC_SDRAM->rcnt &= ~xmc_int; + } + } +} + +/** + * @brief check whether the specified xmc flag is set or not. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - XMC_RISINGEDGE_FLAG + * - XMC_LEVEL_FLAG + * - XMC_FALLINGEDGE_FLAG + * - XMC_FEMPT_FLAG + * - XMC_BUSY_FLAG + * - XMC_ERR_FLAG + * @retval none + */ +flag_status xmc_flag_status_get(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag) +{ + flag_status status = RESET; + uint32_t temp = 0; + + if(xmc_bank == XMC_BANK2_NAND) + { + temp = XMC_BANK2->bk2is; + } + else if(xmc_bank == XMC_BANK3_NAND) + { + temp = XMC_BANK3->bk3is; + } + else if(xmc_bank == XMC_BANK4_PCCARD) + { + temp = XMC_BANK4->bk4is; + } + else + { + temp = XMC_SDRAM->sts; + } + /* get the flag status */ + if((temp & xmc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + /* return the flag status */ + return status; +} + +/** + * @brief clear the xmc's pending flags. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - XMC_RISINGEDGE_FLAG + * - XMC_LEVEL_FLAG + * - XMC_FALLINGEDGE_FLAG + * - XMC_ERR_FLAG + * @retval none + */ +void xmc_flag_clear(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag) +{ + __IO uint32_t int_state; + if(xmc_bank == XMC_BANK2_NAND) + { + int_state = XMC_BANK2->bk2is & 0x38; /* keep interrupt state */ + XMC_BANK2->bk2is = (~(xmc_flag | 0x38) | int_state); + } + else if(xmc_bank == XMC_BANK3_NAND) + { + int_state = XMC_BANK3->bk3is & 0x38; /* keep interrupt state */ + XMC_BANK3->bk3is = (~(xmc_flag | 0x38) | int_state); + } + else if(xmc_bank == XMC_BANK4_PCCARD) + { + int_state = XMC_BANK4->bk4is & 0x38; /* keep interrupt state */ + XMC_BANK4->bk4is = (~(xmc_flag | 0x38) | int_state); + } + else + { + XMC_SDRAM->rcnt |= xmc_flag; + } +} + +/** + * @brief xmc pc card registers reset + * @param none + * @retval none + */ +void xmc_pccard_reset(void) +{ + /* Set the XMC_Bank4 registers to their reset values */ + XMC_BANK4->bk4ctrl = 0x00000018; + XMC_BANK4->bk4is = 0x00000000; + XMC_BANK4->bk4tmgatt = 0xFCFCFCFC; + XMC_BANK4->bk4tmgio = 0xFCFCFCFC; + XMC_BANK4->bk4tmgmem = 0xFCFCFCFC; +} + +/** + * @brief initialize the xmc pccard bank according to the specified + * parameters in the xmc_pccard_init_struct. + * @param xmc_pccard_init_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_init(xmc_pccard_init_type* xmc_pccard_init_struct) +{ + /* set the bk4ctrl register value according to xmc_pccard_init_struct parameters */ + XMC_BANK4->bk4ctrl = (uint32_t)xmc_pccard_init_struct->enable_wait | + XMC_BUSTYPE_16_BITS | + (xmc_pccard_init_struct->delay_time_cr << 9) | + (xmc_pccard_init_struct->delay_time_ar << 13); +} + +/** + * @brief initialize the xmc pccard bank according to the specified + * parameters in the xmc_common_spacetiming_struct/xmc_attribute_spacetiming_struct + * and xmc_iospace_timing_struct. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_special_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_iospace_timing_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_timing_config(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct) +{ + /* set bk4tmgmem register value according to xmc_regular_spacetiming_struct parameters */ + XMC_BANK4->bk4tmgmem = (uint32_t)xmc_regular_spacetiming_struct->mem_setup_time | + (xmc_regular_spacetiming_struct->mem_waite_time << 8) | + (xmc_regular_spacetiming_struct->mem_hold_time << 16) | + (xmc_regular_spacetiming_struct->mem_hiz_time << 24); + + /* Set bk4tmgatt register value according to xmc_special_spacetiming_struct parameters */ + XMC_BANK4->bk4tmgatt = (uint32_t)xmc_special_spacetiming_struct->mem_setup_time | + (xmc_special_spacetiming_struct->mem_waite_time << 8) | + (xmc_special_spacetiming_struct->mem_hold_time << 16) | + (xmc_special_spacetiming_struct->mem_hiz_time << 24); + + /* Set bk4tmgio register value according to xmc_iospace_timing_struct parameters */ + XMC_BANK4->bk4tmgio = (uint32_t)xmc_iospace_timing_struct->mem_setup_time | + (xmc_iospace_timing_struct->mem_waite_time << 8) | + (xmc_iospace_timing_struct->mem_hold_time << 16) | + (xmc_iospace_timing_struct->mem_hiz_time << 24); +} +/** + * @brief fill each xmc_pccard_init_struct member with its default value. + * @param xmc_pccard_init_struct: pointer to a xmc_pccardinittype + * structure which will be initialized. + * @retval none + */ +void xmc_pccard_default_para_init(xmc_pccard_init_type* xmc_pccard_init_struct) +{ + /* reset pccard init structure parameters values */ + xmc_pccard_init_struct->enable_wait = XMC_WAIT_OPERATION_DISABLE; + xmc_pccard_init_struct->delay_time_ar = 0x0; + xmc_pccard_init_struct->delay_time_cr = 0x0; + +} +/** + * @brief fill each xmc_common_spacetiming_struct/xmc_attribute_spacetiming_struct + * and xmc_iospace_timing_struct member with its default value. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_special_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_iospace_timing_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct) +{ + xmc_regular_spacetiming_struct->class_bank = XMC_BANK4_PCCARD; + xmc_regular_spacetiming_struct->mem_hold_time = 0xFC; + xmc_regular_spacetiming_struct->mem_waite_time = 0xFC; + xmc_regular_spacetiming_struct->mem_setup_time = 0xFC; + xmc_regular_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_special_spacetiming_struct->class_bank = XMC_BANK4_PCCARD; + xmc_special_spacetiming_struct->mem_hold_time = 0xFC; + xmc_special_spacetiming_struct->mem_waite_time = 0xFC; + xmc_special_spacetiming_struct->mem_setup_time = 0xFC; + xmc_special_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_iospace_timing_struct->class_bank = XMC_BANK4_PCCARD; + xmc_iospace_timing_struct->mem_hold_time = 0xFC; + xmc_iospace_timing_struct->mem_waite_time = 0xFC; + xmc_iospace_timing_struct->mem_setup_time = 0xFC; + xmc_iospace_timing_struct->mem_hiz_time = 0xFC; +} +/** + * @brief enable or disable the pccard memory bank. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_pccard_enable(confirm_state new_state) +{ + /* enable the pccard bank4 by setting the en bit in the bk4ctrl register */ + XMC_BANK4->bk4ctrl_bit.en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h new file mode 100644 index 0000000000..e0b1d4a281 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h @@ -0,0 +1,783 @@ +/** + ************************************************************************** + * @file at32f435_437.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __AT32F435_437_H +#define __AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined (__CC_ARM) + #pragma anon_unions +#endif + + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437 + * @{ + */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/** + * tip: to avoid modifying this file each time you need to switch between these + * devices, you can define the device in your toolchain compiler preprocessor. + */ + +#if !defined (AT32F435CCU7) && !defined (AT32F435CGU7) && !defined (AT32F435CMU7) && \ + !defined (AT32F435CCT7) && !defined (AT32F435CGT7) && !defined (AT32F435CMT7) && \ + !defined (AT32F435RCT7) && !defined (AT32F435RGT7) && !defined (AT32F435RMT7) && \ + !defined (AT32F435VCT7) && !defined (AT32F435VGT7) && !defined (AT32F435VMT7) && \ + !defined (AT32F435ZCT7) && !defined (AT32F435ZGT7) && !defined (AT32F435ZMT7) && \ + !defined (AT32F437RCT7) && !defined (AT32F437RGT7) && !defined (AT32F437RMT7) && \ + !defined (AT32F437VCT7) && !defined (AT32F437VGT7) && !defined (AT32F437VMT7) && \ + !defined (AT32F437ZCT7) && !defined (AT32F437ZGT7) && !defined (AT32F437ZMT7) + + #error "Please select first the target device used in your application (in at32f435_437.h file)" +#endif + +#if defined (AT32F435CCU7) || defined (AT32F435CGU7) || defined (AT32F435CMU7) || \ + defined (AT32F435CCT7) || defined (AT32F435CGT7) || defined (AT32F435CMT7) || \ + defined (AT32F435RCT7) || defined (AT32F435RGT7) || defined (AT32F435RMT7) || \ + defined (AT32F435VCT7) || defined (AT32F435VGT7) || defined (AT32F435VMT7) || \ + defined (AT32F435ZCT7) || defined (AT32F435ZGT7) || defined (AT32F435ZMT7) + + #define AT32F435xx + //#define AT32F43x +#endif + +#if defined (AT32F437RCT7) || defined (AT32F437RGT7) || defined (AT32F437RMT7) || \ + defined (AT32F437VCT7) || defined (AT32F437VGT7) || defined (AT32F437VMT7) || \ + defined (AT32F437ZCT7) || defined (AT32F437ZGT7) || defined (AT32F437ZMT7) + + #define AT32F437xx + //#define AT32F43x +#endif + +#ifndef USE_STDPERIPH_DRIVER +/** + * @brief comment the line below if you will not use the peripherals drivers. + * in this case, these drivers will not be included and the application code will + * be based on direct access to peripherals registers + */ + #ifdef _RTE_ + #include "RTE_Components.h" + #ifdef RTE_DEVICE_STDPERIPH_FRAMEWORK + #define USE_STDPERIPH_DRIVER + #endif + #endif +#endif + +/** + * @brief at32f435_437 standard peripheral library version number + */ +#define __AT32F435_437_LIBRARY_VERSION_MAJOR (0x02) /*!< [31:24] major version */ +#define __AT32F435_437_LIBRARY_VERSION_MIDDLE (0x01) /*!< [23:16] middle version */ +#define __AT32F435_437_LIBRARY_VERSION_MINOR (0x00) /*!< [15:8] minor version */ +#define __AT32F435_437_LIBRARY_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __AT32F435_437_LIBRARY_VERSION ((__AT32F435_437_LIBRARY_VERSION_MAJOR << 24) | \ + (__AT32F435_437_LIBRARY_VERSION_MIDDLE << 16) | \ + (__AT32F435_437_LIBRARY_VERSION_MINOR << 8) | \ + (__AT32F435_437_LIBRARY_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup configuration_section_for_cmsis + * @{ + */ + +/** + * @brief configuration of the cortex-m4 processor and core peripherals + */ +#define __CM4_REV 0x0001U /*!< core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< mpu present */ +#define __NVIC_PRIO_BITS 4 /*!< at32 uses 4 bits for the priority levels */ +#define __Vendor_SysTickConfig 0 /*!< set to 1 if different systick config is used */ +//#define __FPU_PRESENT 1U /*!< fpu present */ + +/** + * @brief at32f435_437 interrupt number definition, according to the selected device + * in @ref library_configuration_section + */ +typedef enum IRQn +{ + /****** cortex-m4 processor exceptions numbers ***************************************************/ + Reset_IRQn = -15, /*!< 1 reset vector, invoked on power up and warm reset */ + NonMaskableInt_IRQn = -14, /*!< 2 non maskable interrupt */ + HardFault_IRQn = -13, /*!< 3 hard fault, all classes of fault */ + MemoryManagement_IRQn = -12, /*!< 4 cortex-m4 memory management interrupt */ + BusFault_IRQn = -11, /*!< 5 cortex-m4 bus fault interrupt */ + UsageFault_IRQn = -10, /*!< 6 cortex-m4 usage fault interrupt */ + SVCall_IRQn = -5, /*!< 11 cortex-m4 sv call interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 cortex-m4 debug monitor interrupt */ + PendSV_IRQn = -2, /*!< 14 cortex-m4 pend sv interrupt */ + SysTick_IRQn = -1, /*!< 15 cortex-m4 system tick interrupt */ + + /****** at32 specific interrupt numbers *********************************************************/ + WWDT_IRQn = 0, /*!< window watchdog timer interrupt */ + PVM_IRQn = 1, /*!< pvm through exint line detection interrupt */ + TAMP_STAMP_IRQn = 2, /*!< tamper and timestamp interrupts through the exint line */ + ERTC_WKUP_IRQn = 3, /*!< ertc wakeup through the exint line */ + FLASH_IRQn = 4, /*!< flash global interrupt */ + CRM_IRQn = 5, /*!< crm global interrupt */ + EXINT0_IRQn = 6, /*!< exint line0 interrupt */ + EXINT1_IRQn = 7, /*!< exint line1 interrupt */ + EXINT2_IRQn = 8, /*!< exint line2 interrupt */ + EXINT3_IRQn = 9, /*!< exint line3 interrupt */ + EXINT4_IRQn = 10, /*!< exint line4 interrupt */ + EDMA_Stream1_IRQn = 11, /*!< edma stream 1 global interrupt */ + EDMA_Stream2_IRQn = 12, /*!< edma stream 2 global interrupt */ + EDMA_Stream3_IRQn = 13, /*!< edma stream 3 global interrupt */ + EDMA_Stream4_IRQn = 14, /*!< edma stream 4 global interrupt */ + EDMA_Stream5_IRQn = 15, /*!< edma stream 5 global interrupt */ + EDMA_Stream6_IRQn = 16, /*!< edma stream 6 global interrupt */ + EDMA_Stream7_IRQn = 17, /*!< edma stream 7 global interrupt */ + +#if defined (AT32F435xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< edma stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma2 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma2 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma2 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma2 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma2 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma2 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma2 channel 7 global interrupt */ +#endif + +#if defined (AT32F437xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< dma1 stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + EMAC_IRQn = 61, /*!< emac interrupt */ + EMAC_WKUP_IRQn = 62, /*!< emac wakeup interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma2 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma2 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma2 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma2 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma2 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma2 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma2 channel 7 global interrupt */ +#endif + +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" +#include "system_at32f435_437.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +typedef int32_t INT32; +typedef int16_t INT16; +typedef int8_t INT8; +typedef uint32_t UINT32; +typedef uint16_t UINT16; +typedef uint8_t UINT8; + +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< read only */ +typedef const int16_t sc16; /*!< read only */ +typedef const int8_t sc8; /*!< read only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< read only */ +typedef __I int16_t vsc16; /*!< read only */ +typedef __I int8_t vsc8; /*!< read only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< read only */ +typedef const uint16_t uc16; /*!< read only */ +typedef const uint8_t uc8; /*!< read only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< read only */ +typedef __I uint16_t vuc16; /*!< read only */ +typedef __I uint8_t vuc8; /*!< read only */ + +typedef enum {RESET = 0, SET = !RESET} flag_status; +typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state; +typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status; + + + +/** + * @} + */ + +/** @addtogroup Exported_macro + * @{ + */ + +#define REG8(addr) *(volatile uint8_t *)(addr) +#define REG16(addr) *(volatile uint16_t *)(addr) +#define REG32(addr) *(volatile uint32_t *)(addr) + +#define MAKE_VALUE(reg_offset, bit_num) (((reg_offset) << 16) | (bit_num & 0x1f)) + +#define PERIPH_REG(periph_base, value) REG32((periph_base + (value >> 16))) +#define PERIPH_REG_BIT(value) (0x1u << (value & 0x1f)) + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + +#define XMC_SDRAM_MEM_BASE ((uint32_t)0xC0000000) +#define QSPI2_MEM_BASE ((uint32_t)0xB0000000) +#define XMC_CARD_MEM_BASE ((uint32_t)0xA8000000) +#define QSPI2_REG_BASE ((uint32_t)0xA0002000) +#define QSPI1_REG_BASE ((uint32_t)0xA0001000) +#define XMC_REG_BASE ((uint32_t)0xA0000000) +#define XMC_BANK1_REG_BASE (XMC_REG_BASE + 0x0000) +#define XMC_BANK2_REG_BASE (XMC_REG_BASE + 0x0060) +#define XMC_BANK3_REG_BASE (XMC_REG_BASE + 0x0080) +#define XMC_BANK4_REG_BASE (XMC_REG_BASE + 0x00A0) +#define XMC_SDRAM_REG_BASE (XMC_REG_BASE + 0x0140) +#define QSPI1_MEM_BASE ((uint32_t)0x90000000) +#define XMC_MEM_BASE ((uint32_t)0x60000000) +#define PERIPH_BASE ((uint32_t)0x40000000) +#define SRAM_BB_BASE ((uint32_t)0x22000000) +#define PERIPH_BB_BASE ((uint32_t)0x42000000) +#define SRAM_BASE ((uint32_t)0x20000000) +#define USD_BASE ((uint32_t)0x1FFFC000) +#define FLASH_BASE ((uint32_t)0x08000000) + +#define DEBUG_BASE ((uint32_t)0xE0042000) + +#define APB1PERIPH_BASE (PERIPH_BASE) +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH1_BASE (PERIPH_BASE + 0x20000) +#define AHBPERIPH2_BASE (PERIPH_BASE + 0x10000000) + +#if defined (AT32F435xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) +#endif + +#if defined (AT32F437xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define EMAC_BASE (AHBPERIPH1_BASE + 0x8000) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) + +#define EMAC_MAC_BASE (EMAC_BASE) +#define EMAC_MMC_BASE (EMAC_BASE + 0x0100) +#define EMAC_PTP_BASE (EMAC_BASE + 0x0700) +#define EMAC_DMA_BASE (EMAC_BASE + 0x1000) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#include "at32f435_437_def.h" +#include "at32f435_437_conf.h" + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c new file mode 100644 index 0000000000..4c3ddc3565 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c @@ -0,0 +1,142 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief system clock config program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_clock.h" + +/** @addtogroup AT32F437_periph_template + * @{ + */ + +/** @addtogroup 437_System_clock_configuration System_clock_configuration + * @{ + */ + +/** + * @brief system clock config program + * @note the system clock is configured as follow: + * - system clock = (hext * pll_ns)/(pll_ms * pll_fr) + * - system clock source = pll (hext) + * - hext = 8000000 + * - sclk = 288000000 + * - ahbdiv = 1 + * - ahbclk = 288000000 + * - apb2div = 2 + * - apb2clk = 144000000 + * - apb1div = 2 + * - apb1clk = 144000000 + * - pll_ns = 72 + * - pll_ms = 1 + * - pll_fr = 2 + * @param none + * @retval none + */ +void system_clock_config(void) +{ + /* enable pwc periph clock */ + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + + /* config ldo voltage */ + pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3); + + /* set the flash clock divider */ + flash_clock_divider_set(FLASH_CLOCK_DIV_3); + + /* reset crm */ + crm_reset(); + + crm_clock_source_enable(CRM_CLOCK_SOURCE_HEXT, TRUE); + + /* wait till hext is ready */ + while(crm_hext_stable_wait() == ERROR) + { + } + + /* config pll clock resource + common frequency config list: pll source selected hick or hext(8mhz) + _______________________________________________________________________________________ + | | | | | | | | | | + |pll(mhz)| 288 | 252 | 216 | 180 | 144 | 108 | 72 | 36 | + |________|_________|_________|_________|_________|_________|_________|_________________| + | | | | | | | | | | + |pll_ns | 72 | 63 | 108 | 90 | 72 | 108 | 72 | 72 | + | | | | | | | | | | + |pll_ms | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | + | | | | | | | | | | + |pll_fr | FR_2 | FR_2 | FR_4 | FR_4 | FR_4 | FR_8 | FR_8 | FR_16| + |________|_________|_________|_________|_________|_________|_________|________|________| + + if pll clock source selects hext with other frequency values, or configure pll to other + frequency values, please use the at32 new clock configuration tool for configuration. */ + crm_pll_config(CRM_PLL_SOURCE_HEXT, 72, 1, CRM_PLL_FR_2); + + /* enable pll */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); + + /* wait till pll is ready */ + while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) + { + } + + /* config ahbclk */ + crm_ahb_div_set(CRM_AHB_DIV_1); + + /* config apb2clk */ + crm_apb2_div_set(CRM_APB2_DIV_2); + + /* config apb1clk */ + crm_apb1_div_set(CRM_APB1_DIV_2); + + /* enable auto step mode */ + crm_auto_step_mode_enable(TRUE); + + /* select pll as system clock source */ + crm_sysclk_switch(CRM_SCLK_PLL); + + /* wait till pll is used as system clock source */ + while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL) + { + } + + /* disable auto step mode */ + crm_auto_step_mode_enable(FALSE); + + /* config usbclk from pll */ + crm_usb_clock_div_set(CRM_USB_DIV_6); + crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_PLL); + + /* update system_core_clock global variable */ + system_core_clock_update(); +} + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h new file mode 100644 index 0000000000..5199f2b4c0 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h @@ -0,0 +1,46 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief header file of clock program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CLOCK_H +#define __AT32F435_437_CLOCK_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/* exported functions ------------------------------------------------------- */ +void system_clock_config(void); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h new file mode 100644 index 0000000000..d715960033 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h @@ -0,0 +1,249 @@ +/** + ************************************************************************** + * @file at32f435_437_conf.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CONF_H +#define __AT32F435_437_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef NULL +#ifdef __cplusplus +#define NULL 0 +#else +#define NULL ((void *) 0) +#endif +#endif + + +/** @addtogroup AT32F437_periph_template + * @{ + */ + +/** @addtogroup 437_Library_configuration Library_configuration + * @{ + */ + +/** + * @brief in the following line adjust the value of high speed exernal crystal (hext) + * used in your application + * + * tip: to avoid modifying this file each time you need to use different hext, you + * can define the hext value in your toolchain compiler preprocessor. + * + */ +#if !defined HEXT_VALUE +#define HEXT_VALUE ((uint32_t)8000000) /*!< value of the high speed exernal crystal in hz */ +#endif + +/** + * @brief in the following line adjust the high speed exernal crystal (hext) startup + * timeout value + */ +#define HEXT_STARTUP_TIMEOUT ((uint16_t)0x3000) /*!< time out for hext start up */ +#define HICK_VALUE ((uint32_t)8000000) /*!< value of the high speed internal clock in hz */ + +/* module define -------------------------------------------------------------*/ +#define CRM_MODULE_ENABLED +#define TMR_MODULE_ENABLED +#define ERTC_MODULE_ENABLED +#define GPIO_MODULE_ENABLED +#define I2C_MODULE_ENABLED +#define USART_MODULE_ENABLED +#define PWC_MODULE_ENABLED +#define CAN_MODULE_ENABLED +#define ADC_MODULE_ENABLED +#define DAC_MODULE_ENABLED +#define SPI_MODULE_ENABLED +#define EDMA_MODULE_ENABLED +#define DMA_MODULE_ENABLED +#define DEBUG_MODULE_ENABLED +#define FLASH_MODULE_ENABLED +#define CRC_MODULE_ENABLED +#define WWDT_MODULE_ENABLED +#define WDT_MODULE_ENABLED +#define EXINT_MODULE_ENABLED +#define SDIO_MODULE_ENABLED +#define XMC_MODULE_ENABLED +#define USB_MODULE_ENABLED +#define ACC_MODULE_ENABLED +#define MISC_MODULE_ENABLED +#define QSPI_MODULE_ENABLED +#define DVP_MODULE_ENABLED +#define SCFG_MODULE_ENABLED +#define EMAC_MODULE_ENABLED + +/* includes ------------------------------------------------------------------*/ +#ifdef CRM_MODULE_ENABLED +#include "at32f435_437_crm.h" +#endif +#ifdef TMR_MODULE_ENABLED + +#include "at32f435_437_tmr.h" + +#endif +#ifdef ERTC_MODULE_ENABLED + +#include "at32f435_437_ertc.h" + +#endif +#ifdef GPIO_MODULE_ENABLED + +#include "at32f435_437_gpio.h" + +#endif +#ifdef I2C_MODULE_ENABLED + +#include "at32f435_437_i2c.h" + +#endif +#ifdef USART_MODULE_ENABLED + +#include "at32f435_437_usart.h" + +#endif +#ifdef PWC_MODULE_ENABLED + +#include "at32f435_437_pwc.h" + +#endif +#ifdef CAN_MODULE_ENABLED + +#include "at32f435_437_can.h" + +#endif +#ifdef ADC_MODULE_ENABLED + +#include "at32f435_437_adc.h" + +#endif +#ifdef DAC_MODULE_ENABLED + +#include "at32f435_437_dac.h" + +#endif +#ifdef SPI_MODULE_ENABLED + +#include "at32f435_437_spi.h" + +#endif +#ifdef DMA_MODULE_ENABLED + +#include "at32f435_437_dma.h" + +#endif +#ifdef DEBUG_MODULE_ENABLED + +#include "at32f435_437_debug.h" + +#endif +#ifdef FLASH_MODULE_ENABLED + +#include "at32f435_437_flash.h" + +#endif +#ifdef CRC_MODULE_ENABLED + +#include "at32f435_437_crc.h" + +#endif +#ifdef WWDT_MODULE_ENABLED + +#include "at32f435_437_wwdt.h" + +#endif +#ifdef WDT_MODULE_ENABLED + +#include "at32f435_437_wdt.h" + +#endif +#ifdef EXINT_MODULE_ENABLED + +#include "at32f435_437_exint.h" + +#endif +#ifdef SDIO_MODULE_ENABLED + +#include "at32f435_437_sdio.h" + +#endif +#ifdef XMC_MODULE_ENABLED + +#include "at32f435_437_xmc.h" + +#endif +#ifdef ACC_MODULE_ENABLED + +#include "at32f435_437_acc.h" + +#endif +#ifdef MISC_MODULE_ENABLED + +#include "at32f435_437_misc.h" + +#endif +#ifdef EDMA_MODULE_ENABLED + +#include "at32f435_437_edma.h" + +#endif +#ifdef QSPI_MODULE_ENABLED +#include "at32f435_437_qspi.h" + +#endif +#ifdef SCFG_MODULE_ENABLED +#include "at32f435_437_scfg.h" + +#endif +#ifdef EMAC_MODULE_ENABLED +#include "at32f435_437_emac.h" + +#endif +#ifdef DVP_MODULE_ENABLED +#include "at32f435_437_dvp.h" + +#endif +#ifdef USB_MODULE_ENABLED + +#include "at32f435_437_usb.h" + +#endif + +/** + * @} + */ + + /** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h new file mode 100644 index 0000000000..721b18dd2d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h @@ -0,0 +1,517 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_common_tables.h + * Description: Extern declaration for common tables + * + * $Date: 27. January 2017 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_COMMON_TABLES_H +#define _ARM_COMMON_TABLES_H + +#include "arm_math.h" + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + /* Double Precision Float CFFT twiddles */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREV_1024) + extern const uint16_t armBitRevTable[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_16) + extern const uint64_t twiddleCoefF64_16[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_32) + extern const uint64_t twiddleCoefF64_32[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_64) + extern const uint64_t twiddleCoefF64_64[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_128) + extern const uint64_t twiddleCoefF64_128[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_256) + extern const uint64_t twiddleCoefF64_256[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_512) + extern const uint64_t twiddleCoefF64_512[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_1024) + extern const uint64_t twiddleCoefF64_1024[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_2048) + extern const uint64_t twiddleCoefF64_2048[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_4096) + extern const uint64_t twiddleCoefF64_4096[8192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_16) + extern const float32_t twiddleCoef_16[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_32) + extern const float32_t twiddleCoef_32[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_64) + extern const float32_t twiddleCoef_64[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_128) + extern const float32_t twiddleCoef_128[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_256) + extern const float32_t twiddleCoef_256[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_512) + extern const float32_t twiddleCoef_512[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_1024) + extern const float32_t twiddleCoef_1024[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_2048) + extern const float32_t twiddleCoef_2048[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_4096) + extern const float32_t twiddleCoef_4096[8192]; + #define twiddleCoef twiddleCoef_4096 + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_16) + extern const q31_t twiddleCoef_16_q31[24]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_32) + extern const q31_t twiddleCoef_32_q31[48]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_64) + extern const q31_t twiddleCoef_64_q31[96]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_128) + extern const q31_t twiddleCoef_128_q31[192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_256) + extern const q31_t twiddleCoef_256_q31[384]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_512) + extern const q31_t twiddleCoef_512_q31[768]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_1024) + extern const q31_t twiddleCoef_1024_q31[1536]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_2048) + extern const q31_t twiddleCoef_2048_q31[3072]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_4096) + extern const q31_t twiddleCoef_4096_q31[6144]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_16) + extern const q15_t twiddleCoef_16_q15[24]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_32) + extern const q15_t twiddleCoef_32_q15[48]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_64) + extern const q15_t twiddleCoef_64_q15[96]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_128) + extern const q15_t twiddleCoef_128_q15[192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_256) + extern const q15_t twiddleCoef_256_q15[384]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_512) + extern const q15_t twiddleCoef_512_q15[768]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_1024) + extern const q15_t twiddleCoef_1024_q15[1536]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_2048) + extern const q15_t twiddleCoef_2048_q15[3072]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_4096) + extern const q15_t twiddleCoef_4096_q15[6144]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + /* Double Precision Float RFFT twiddles */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_32) + extern const uint64_t twiddleCoefF64_rfft_32[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_64) + extern const uint64_t twiddleCoefF64_rfft_64[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_128) + extern const uint64_t twiddleCoefF64_rfft_128[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_256) + extern const uint64_t twiddleCoefF64_rfft_256[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_512) + extern const uint64_t twiddleCoefF64_rfft_512[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_1024) + extern const uint64_t twiddleCoefF64_rfft_1024[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_2048) + extern const uint64_t twiddleCoefF64_rfft_2048[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_4096) + extern const uint64_t twiddleCoefF64_rfft_4096[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_32) + extern const float32_t twiddleCoef_rfft_32[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_64) + extern const float32_t twiddleCoef_rfft_64[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_128) + extern const float32_t twiddleCoef_rfft_128[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_256) + extern const float32_t twiddleCoef_rfft_256[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_512) + extern const float32_t twiddleCoef_rfft_512[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_1024) + extern const float32_t twiddleCoef_rfft_1024[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_2048) + extern const float32_t twiddleCoef_rfft_2048[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_4096) + extern const float32_t twiddleCoef_rfft_4096[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + /* Double precision floating-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_16) + #define ARMBITREVINDEXTABLEF64_16_TABLE_LENGTH ((uint16_t)12) + extern const uint16_t armBitRevIndexTableF64_16[ARMBITREVINDEXTABLEF64_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_32) + #define ARMBITREVINDEXTABLEF64_32_TABLE_LENGTH ((uint16_t)24) + extern const uint16_t armBitRevIndexTableF64_32[ARMBITREVINDEXTABLEF64_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_64) + #define ARMBITREVINDEXTABLEF64_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTableF64_64[ARMBITREVINDEXTABLEF64_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_128) + #define ARMBITREVINDEXTABLEF64_128_TABLE_LENGTH ((uint16_t)112) + extern const uint16_t armBitRevIndexTableF64_128[ARMBITREVINDEXTABLEF64_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_256) + #define ARMBITREVINDEXTABLEF64_256_TABLE_LENGTH ((uint16_t)240) + extern const uint16_t armBitRevIndexTableF64_256[ARMBITREVINDEXTABLEF64_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_512) + #define ARMBITREVINDEXTABLEF64_512_TABLE_LENGTH ((uint16_t)480) + extern const uint16_t armBitRevIndexTableF64_512[ARMBITREVINDEXTABLEF64_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_1024) + #define ARMBITREVINDEXTABLEF64_1024_TABLE_LENGTH ((uint16_t)992) + extern const uint16_t armBitRevIndexTableF64_1024[ARMBITREVINDEXTABLEF64_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_2048) + #define ARMBITREVINDEXTABLEF64_2048_TABLE_LENGTH ((uint16_t)1984) + extern const uint16_t armBitRevIndexTableF64_2048[ARMBITREVINDEXTABLEF64_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_4096) + #define ARMBITREVINDEXTABLEF64_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTableF64_4096[ARMBITREVINDEXTABLEF64_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + /* floating-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_16) + #define ARMBITREVINDEXTABLE_16_TABLE_LENGTH ((uint16_t)20) + extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_32) + #define ARMBITREVINDEXTABLE_32_TABLE_LENGTH ((uint16_t)48) + extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_64) + #define ARMBITREVINDEXTABLE_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_128) + #define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208) + extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_256) + #define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440) + extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_512) + #define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448) + extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_1024) + #define ARMBITREVINDEXTABLE_1024_TABLE_LENGTH ((uint16_t)1800) + extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_2048) + #define ARMBITREVINDEXTABLE_2048_TABLE_LENGTH ((uint16_t)3808) + extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_4096) + #define ARMBITREVINDEXTABLE_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + /* fixed-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_16) + #define ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH ((uint16_t)12) + extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_32) + #define ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH ((uint16_t)24) + extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_64) + #define ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_128) + #define ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH ((uint16_t)112) + extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_256) + #define ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH ((uint16_t)240) + extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_512) + #define ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH ((uint16_t)480) + extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_1024) + #define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992) + extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_2048) + #define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984) + extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_4096) + #define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_F32) + extern const float32_t realCoefA[8192]; + extern const float32_t realCoefB[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q31) + extern const q31_t realCoefAQ31[8192]; + extern const q31_t realCoefBQ31[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q15) + extern const q15_t realCoefAQ15[8192]; + extern const q15_t realCoefBQ15[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_128) + extern const float32_t Weights_128[256]; + extern const float32_t cos_factors_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_512) + extern const float32_t Weights_512[1024]; + extern const float32_t cos_factors_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_2048) + extern const float32_t Weights_2048[4096]; + extern const float32_t cos_factors_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_8192) + extern const float32_t Weights_8192[16384]; + extern const float32_t cos_factors_8192[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_128) + extern const q15_t WeightsQ15_128[256]; + extern const q15_t cos_factorsQ15_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_512) + extern const q15_t WeightsQ15_512[1024]; + extern const q15_t cos_factorsQ15_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_2048) + extern const q15_t WeightsQ15_2048[4096]; + extern const q15_t cos_factorsQ15_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_8192) + extern const q15_t WeightsQ15_8192[16384]; + extern const q15_t cos_factorsQ15_8192[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_128) + extern const q31_t WeightsQ31_128[256]; + extern const q31_t cos_factorsQ31_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_512) + extern const q31_t WeightsQ31_512[1024]; + extern const q31_t cos_factorsQ31_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_2048) + extern const q31_t WeightsQ31_2048[4096]; + extern const q31_t cos_factorsQ31_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_8192) + extern const q31_t WeightsQ31_8192[16384]; + extern const q31_t cos_factorsQ31_8192[8192]; + #endif + +#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_TABLES) */ + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_ALLOW_TABLES) + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q15) + extern const q15_t armRecipTableQ15[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q31) + extern const q31_t armRecipTableQ31[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + /* Tables for Fast Math Sine and Cosine */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_F32) + extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q31) + extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q15) + extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if defined(ARM_MATH_MVEI) + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q31_MVE) + extern const q31_t sqrtTable_Q31[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + #endif + + #if defined(ARM_MATH_MVEI) + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q15_MVE) + extern const q15_t sqrtTable_Q15[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + #endif + +#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_TABLES) */ + +#if (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) + extern const float32_t exp_tab[8]; + extern const float32_t __logf_lut_f32[8]; +#endif /* (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) */ + +#if (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) +extern const unsigned char hwLUT[256]; +#endif /* (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) */ + +#endif /* ARM_COMMON_TABLES_H */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h new file mode 100644 index 0000000000..83984c40cd --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h @@ -0,0 +1,76 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_const_structs.h + * Description: Constant structs that are initialized for user convenience. + * For example, some can be given as arguments to the arm_cfft_f32() function. + * + * $Date: 27. January 2017 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_CONST_STRUCTS_H +#define _ARM_CONST_STRUCTS_H + +#include "arm_math.h" +#include "arm_common_tables.h" + + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len16; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len32; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len64; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len128; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len256; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len512; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len1024; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len2048; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len4096; + + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096; + + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096; + + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096; + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h new file mode 100644 index 0000000000..7609d329f0 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h @@ -0,0 +1,348 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_helium_utils.h + * Description: Utility functions for Helium development + * + * $Date: 09. September 2019 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2019 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_UTILS_HELIUM_H_ +#define _ARM_UTILS_HELIUM_H_ + +/*************************************** + +Definitions available for MVEF and MVEI + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) + +#define INACTIVELANE 0 /* inactive lane content */ + + +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) */ + +/*************************************** + +Definitions available for MVEF only + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) + +__STATIC_FORCEINLINE float32_t vecAddAcrossF32Mve(float32x4_t in) +{ + float32_t acc; + + acc = vgetq_lane(in, 0) + vgetq_lane(in, 1) + + vgetq_lane(in, 2) + vgetq_lane(in, 3); + + return acc; +} + +/* newton initial guess */ +#define INVSQRT_MAGIC_F32 0x5f3759df + +#define INVSQRT_NEWTON_MVE_F32(invSqrt, xHalf, xStart)\ +{ \ + float32x4_t tmp; \ + \ + /* tmp = xhalf * x * x */ \ + tmp = vmulq(xStart, xStart); \ + tmp = vmulq(tmp, xHalf); \ + /* (1.5f - xhalf * x * x) */ \ + tmp = vsubq(vdupq_n_f32(1.5f), tmp); \ + /* x = x*(1.5f-xhalf*x*x); */ \ + invSqrt = vmulq(tmp, xStart); \ +} +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) */ + +/*************************************** + +Definitions available for MVEI only + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEI) + + +#include "arm_common_tables.h" + +/* Following functions are used to transpose matrix in f32 and q31 cases */ +__STATIC_INLINE arm_status arm_mat_trans_32bit_2x2_mve( + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + static const uint32x4_t vecOffs = { 0, 2, 1, 3 }; + /* + * + * | 0 1 | => | 0 2 | + * | 2 3 | | 1 3 | + * + */ + uint32x4_t vecIn = vldrwq_u32((uint32_t const *)pDataSrc); + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs, vecIn); + + return (ARM_MATH_SUCCESS); +} + +__STATIC_INLINE arm_status arm_mat_trans_32bit_3x3_mve( + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + const uint32x4_t vecOffs1 = { 0, 3, 6, 1}; + const uint32x4_t vecOffs2 = { 4, 7, 2, 5}; + /* + * + * | 0 1 2 | | 0 3 6 | 4 x 32 flattened version | 0 3 6 1 | + * | 3 4 5 | => | 1 4 7 | => | 4 7 2 5 | + * | 6 7 8 | | 2 5 8 | (row major) | 8 . . . | + * + */ + uint32x4_t vecIn1 = vldrwq_u32((uint32_t const *) pDataSrc); + uint32x4_t vecIn2 = vldrwq_u32((uint32_t const *) &pDataSrc[4]); + + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs1, vecIn1); + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs2, vecIn2); + + pDataDest[8] = pDataSrc[8]; + + return (ARM_MATH_SUCCESS); +} + +__STATIC_INLINE arm_status arm_mat_trans_32bit_4x4_mve(uint32_t * pDataSrc, uint32_t * pDataDest) +{ + /* + * 4x4 Matrix transposition + * is 4 x de-interleave operation + * + * 0 1 2 3 0 4 8 12 + * 4 5 6 7 1 5 9 13 + * 8 9 10 11 2 6 10 14 + * 12 13 14 15 3 7 11 15 + */ + + uint32x4x4_t vecIn; + + vecIn = vld4q((uint32_t const *) pDataSrc); + vstrwq(pDataDest, vecIn.val[0]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[1]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[2]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[3]); + + return (ARM_MATH_SUCCESS); +} + + +__STATIC_INLINE arm_status arm_mat_trans_32bit_generic_mve( + uint16_t srcRows, + uint16_t srcCols, + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + uint32x4_t vecOffs; + uint32_t i; + uint32_t blkCnt; + uint32_t const *pDataC; + uint32_t *pDataDestR; + uint32x4_t vecIn; + + vecOffs = vidupq_u32((uint32_t)0, 1); + vecOffs = vecOffs * srcCols; + + i = srcCols; + do + { + pDataC = (uint32_t const *) pDataSrc; + pDataDestR = pDataDest; + + blkCnt = srcRows >> 2; + while (blkCnt > 0U) + { + vecIn = vldrwq_gather_shifted_offset_u32(pDataC, vecOffs); + vstrwq(pDataDestR, vecIn); + pDataDestR += 4; + pDataC = pDataC + srcCols * 4; + /* + * Decrement the blockSize loop counter + */ + blkCnt--; + } + + /* + * tail + */ + blkCnt = srcRows & 3; + if (blkCnt > 0U) + { + mve_pred16_t p0 = vctp32q(blkCnt); + vecIn = vldrwq_gather_shifted_offset_u32(pDataC, vecOffs); + vstrwq_p(pDataDestR, vecIn, p0); + } + + pDataSrc += 1; + pDataDest += srcRows; + } + while (--i); + + return (ARM_MATH_SUCCESS); +} + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q31_MVE) +__STATIC_INLINE q31x4_t FAST_VSQRT_Q31(q31x4_t vecIn) +{ + q63x2_t vecTmpLL; + q31x4_t vecTmp0, vecTmp1; + q31_t scale; + q63_t tmp64; + q31x4_t vecNrm, vecDst, vecIdx, vecSignBits; + + + vecSignBits = vclsq(vecIn); + vecSignBits = vbicq(vecSignBits, 1); + /* + * in = in << no_of_sign_bits; + */ + vecNrm = vshlq(vecIn, vecSignBits); + /* + * index = in >> 24; + */ + vecIdx = vecNrm >> 24; + vecIdx = vecIdx << 1; + + vecTmp0 = vldrwq_gather_shifted_offset_s32(sqrtTable_Q31, vecIdx); + + vecIdx = vecIdx + 1; + + vecTmp1 = vldrwq_gather_shifted_offset_s32(sqrtTable_Q31, vecIdx); + + vecTmp1 = vqrdmulhq(vecTmp1, vecNrm); + vecTmp0 = vecTmp0 - vecTmp1; + vecTmp1 = vqrdmulhq(vecTmp0, vecTmp0); + vecTmp1 = vqrdmulhq(vecNrm, vecTmp1); + vecTmp1 = vdupq_n_s32(0x18000000) - vecTmp1; + vecTmp0 = vqrdmulhq(vecTmp0, vecTmp1); + vecTmpLL = vmullbq_int(vecNrm, vecTmp0); + + /* + * scale elements 0, 2 + */ + scale = 26 + (vecSignBits[0] >> 1); + tmp64 = asrl(vecTmpLL[0], scale); + vecDst[0] = (q31_t) tmp64; + + scale = 26 + (vecSignBits[2] >> 1); + tmp64 = asrl(vecTmpLL[1], scale); + vecDst[2] = (q31_t) tmp64; + + vecTmpLL = vmulltq_int(vecNrm, vecTmp0); + + /* + * scale elements 1, 3 + */ + scale = 26 + (vecSignBits[1] >> 1); + tmp64 = asrl(vecTmpLL[0], scale); + vecDst[1] = (q31_t) tmp64; + + scale = 26 + (vecSignBits[3] >> 1); + tmp64 = asrl(vecTmpLL[1], scale); + vecDst[3] = (q31_t) tmp64; + /* + * set negative values to 0 + */ + vecDst = vdupq_m(vecDst, 0, vcmpltq_n_s32(vecIn, 0)); + + return vecDst; +} +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q15_MVE) +__STATIC_INLINE q15x8_t FAST_VSQRT_Q15(q15x8_t vecIn) +{ + q31x4_t vecTmpLev, vecTmpLodd, vecSignL; + q15x8_t vecTmp0, vecTmp1; + q15x8_t vecNrm, vecDst, vecIdx, vecSignBits; + + vecDst = vuninitializedq_s16(); + + vecSignBits = vclsq(vecIn); + vecSignBits = vbicq(vecSignBits, 1); + /* + * in = in << no_of_sign_bits; + */ + vecNrm = vshlq(vecIn, vecSignBits); + + vecIdx = vecNrm >> 8; + vecIdx = vecIdx << 1; + + vecTmp0 = vldrhq_gather_shifted_offset_s16(sqrtTable_Q15, vecIdx); + + vecIdx = vecIdx + 1; + + vecTmp1 = vldrhq_gather_shifted_offset_s16(sqrtTable_Q15, vecIdx); + + vecTmp1 = vqrdmulhq(vecTmp1, vecNrm); + vecTmp0 = vecTmp0 - vecTmp1; + vecTmp1 = vqrdmulhq(vecTmp0, vecTmp0); + vecTmp1 = vqrdmulhq(vecNrm, vecTmp1); + vecTmp1 = vdupq_n_s16(0x1800) - vecTmp1; + vecTmp0 = vqrdmulhq(vecTmp0, vecTmp1); + + vecSignBits = vecSignBits >> 1; + + vecTmpLev = vmullbq_int(vecNrm, vecTmp0); + vecTmpLodd = vmulltq_int(vecNrm, vecTmp0); + + vecTmp0 = vecSignBits + 10; + /* + * negate sign to apply register based vshl + */ + vecTmp0 = -vecTmp0; + + /* + * shift even elements + */ + vecSignL = vmovlbq(vecTmp0); + vecTmpLev = vshlq(vecTmpLev, vecSignL); + /* + * shift odd elements + */ + vecSignL = vmovltq(vecTmp0); + vecTmpLodd = vshlq(vecTmpLodd, vecSignL); + /* + * merge and narrow odd and even parts + */ + vecDst = vmovnbq_s32(vecDst, vecTmpLev); + vecDst = vmovntq_s32(vecDst, vecTmpLodd); + /* + * set negative values to 0 + */ + vecDst = vdupq_m(vecDst, 0, vcmpltq_n_s16(vecIn, 0)); + + return vecDst; +} +#endif + +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEI) */ + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h new file mode 100644 index 0000000000..48bee62cd9 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h @@ -0,0 +1,8970 @@ +/****************************************************************************** + * @file arm_math.h + * @brief Public header file for CMSIS DSP Library + * @version V1.7.0 + * @date 18. March 2019 + ******************************************************************************/ +/* + * Copyright (c) 2010-2019 Arm Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + \mainpage CMSIS DSP Software Library + * + * Introduction + * ------------ + * + * This user manual describes the CMSIS DSP software library, + * a suite of common signal processing functions for use on Cortex-M and Cortex-A processor + * based devices. + * + * The library is divided into a number of functions each covering a specific category: + * - Basic math functions + * - Fast math functions + * - Complex math functions + * - Filtering functions + * - Matrix functions + * - Transform functions + * - Motor control functions + * - Statistical functions + * - Support functions + * - Interpolation functions + * - Support Vector Machine functions (SVM) + * - Bayes classifier functions + * - Distance functions + * + * The library has generally separate functions for operating on 8-bit integers, 16-bit integers, + * 32-bit integer and 32-bit floating-point values. + * + * Using the Library + * ------------ + * + * The library installer contains prebuilt versions of the libraries in the Lib folder. + * + * Here is the list of pre-built libraries : + * - arm_cortexM7lfdp_math.lib (Cortex-M7, Little endian, Double Precision Floating Point Unit) + * - arm_cortexM7bfdp_math.lib (Cortex-M7, Big endian, Double Precision Floating Point Unit) + * - arm_cortexM7lfsp_math.lib (Cortex-M7, Little endian, Single Precision Floating Point Unit) + * - arm_cortexM7bfsp_math.lib (Cortex-M7, Big endian and Single Precision Floating Point Unit on) + * - arm_cortexM7l_math.lib (Cortex-M7, Little endian) + * - arm_cortexM7b_math.lib (Cortex-M7, Big endian) + * - arm_cortexM4lf_math.lib (Cortex-M4, Little endian, Floating Point Unit) + * - arm_cortexM4bf_math.lib (Cortex-M4, Big endian, Floating Point Unit) + * - arm_cortexM4l_math.lib (Cortex-M4, Little endian) + * - arm_cortexM4b_math.lib (Cortex-M4, Big endian) + * - arm_cortexM3l_math.lib (Cortex-M3, Little endian) + * - arm_cortexM3b_math.lib (Cortex-M3, Big endian) + * - arm_cortexM0l_math.lib (Cortex-M0 / Cortex-M0+, Little endian) + * - arm_cortexM0b_math.lib (Cortex-M0 / Cortex-M0+, Big endian) + * - arm_ARMv8MBLl_math.lib (Armv8-M Baseline, Little endian) + * - arm_ARMv8MMLl_math.lib (Armv8-M Mainline, Little endian) + * - arm_ARMv8MMLlfsp_math.lib (Armv8-M Mainline, Little endian, Single Precision Floating Point Unit) + * - arm_ARMv8MMLld_math.lib (Armv8-M Mainline, Little endian, DSP instructions) + * - arm_ARMv8MMLldfsp_math.lib (Armv8-M Mainline, Little endian, DSP instructions, Single Precision Floating Point Unit) + * + * The library functions are declared in the public file arm_math.h which is placed in the Include folder. + * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single + * public header file arm_math.h for Cortex-M cores with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. + * + * + * Examples + * -------- + * + * The library ships with a number of examples which demonstrate how to use the library functions. + * + * Toolchain Support + * ------------ + * + * The library is now tested on Fast Models building with cmake. + * Core M0, M7, A5 are tested. + * + * + * + * Building the Library + * ------------ + * + * The library installer contains a project file to rebuild libraries on MDK toolchain in the CMSIS\\DSP\\Projects\\ARM folder. + * - arm_cortexM_math.uvprojx + * + * + * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional preprocessor macros detailed above. + * + * There is also a work in progress cmake build. The README file is giving more details. + * + * Preprocessor Macros + * ------------ + * + * Each library project have different preprocessor macros. + * + * - ARM_MATH_BIG_ENDIAN: + * + * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. + * + * - ARM_MATH_MATRIX_CHECK: + * + * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices + * + * - ARM_MATH_ROUNDING: + * + * Define macro ARM_MATH_ROUNDING for rounding on support functions + * + * - ARM_MATH_LOOPUNROLL: + * + * Define macro ARM_MATH_LOOPUNROLL to enable manual loop unrolling in DSP functions + * + * - ARM_MATH_NEON: + * + * Define macro ARM_MATH_NEON to enable Neon versions of the DSP functions. + * It is not enabled by default when Neon is available because performances are + * dependent on the compiler and target architecture. + * + * - ARM_MATH_NEON_EXPERIMENTAL: + * + * Define macro ARM_MATH_NEON_EXPERIMENTAL to enable experimental Neon versions of + * of some DSP functions. Experimental Neon versions currently do not have better + * performances than the scalar versions. + * + * - ARM_MATH_HELIUM: + * + * It implies the flags ARM_MATH_MVEF and ARM_MATH_MVEI and ARM_MATH_FLOAT16. + * + * - ARM_MATH_MVEF: + * + * Select Helium versions of the f32 algorithms. + * It implies ARM_MATH_FLOAT16 and ARM_MATH_MVEI. + * + * - ARM_MATH_MVEI: + * + * Select Helium versions of the int and fixed point algorithms. + * + * - ARM_MATH_FLOAT16: + * + * Float16 implementations of some algorithms (Requires MVE extension). + * + *
+ * CMSIS-DSP in ARM::CMSIS Pack + * ----------------------------- + * + * The following files relevant to CMSIS-DSP are present in the ARM::CMSIS Pack directories: + * |File/Folder |Content | + * |---------------------------------|------------------------------------------------------------------------| + * |\b CMSIS\\Documentation\\DSP | This documentation | + * |\b CMSIS\\DSP\\DSP_Lib_TestSuite | DSP_Lib test suite | + * |\b CMSIS\\DSP\\Examples | Example projects demonstrating the usage of the library functions | + * |\b CMSIS\\DSP\\Include | DSP_Lib include files | + * |\b CMSIS\\DSP\\Lib | DSP_Lib binaries | + * |\b CMSIS\\DSP\\Projects | Projects to rebuild DSP_Lib binaries | + * |\b CMSIS\\DSP\\Source | DSP_Lib source files | + * + *
+ * Revision History of CMSIS-DSP + * ------------ + * Please refer to \ref ChangeLog_pg. + */ + + +/** + * @defgroup groupMath Basic Math Functions + */ + +/** + * @defgroup groupFastMath Fast Math Functions + * This set of functions provides a fast approximation to sine, cosine, and square root. + * As compared to most of the other functions in the CMSIS math library, the fast math functions + * operate on individual values and not arrays. + * There are separate functions for Q15, Q31, and floating-point data. + * + */ + +/** + * @defgroup groupCmplxMath Complex Math Functions + * This set of functions operates on complex data vectors. + * The data in the complex arrays is stored in an interleaved fashion + * (real, imag, real, imag, ...). + * In the API functions, the number of samples in a complex array refers + * to the number of complex values; the array contains twice this number of + * real values. + */ + +/** + * @defgroup groupFilters Filtering Functions + */ + +/** + * @defgroup groupMatrix Matrix Functions + * + * This set of functions provides basic matrix math operations. + * The functions operate on matrix data structures. For example, + * the type + * definition for the floating-point matrix structure is shown + * below: + *
+ *     typedef struct
+ *     {
+ *       uint16_t numRows;     // number of rows of the matrix.
+ *       uint16_t numCols;     // number of columns of the matrix.
+ *       float32_t *pData;     // points to the data of the matrix.
+ *     } arm_matrix_instance_f32;
+ * 
+ * There are similar definitions for Q15 and Q31 data types. + * + * The structure specifies the size of the matrix and then points to + * an array of data. The array is of size numRows X numCols + * and the values are arranged in row order. That is, the + * matrix element (i, j) is stored at: + *
+ *     pData[i*numCols + j]
+ * 
+ * + * \par Init Functions + * There is an associated initialization function for each type of matrix + * data structure. + * The initialization function sets the values of the internal structure fields. + * Refer to \ref arm_mat_init_f32(), \ref arm_mat_init_q31() and \ref arm_mat_init_q15() + * for floating-point, Q31 and Q15 types, respectively. + * + * \par + * Use of the initialization function is optional. However, if initialization function is used + * then the instance structure cannot be placed into a const data section. + * To place the instance structure in a const data + * section, manually initialize the data structure. For example: + *
+ * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
+ * 
+ * where nRows specifies the number of rows, nColumns + * specifies the number of columns, and pData points to the + * data array. + * + * \par Size Checking + * By default all of the matrix functions perform size checking on the input and + * output matrices. For example, the matrix addition function verifies that the + * two input matrices and the output matrix all have the same number of rows and + * columns. If the size check fails the functions return: + *
+ *     ARM_MATH_SIZE_MISMATCH
+ * 
+ * Otherwise the functions return + *
+ *     ARM_MATH_SUCCESS
+ * 
+ * There is some overhead associated with this matrix size checking. + * The matrix size checking is enabled via the \#define + *
+ *     ARM_MATH_MATRIX_CHECK
+ * 
+ * within the library project settings. By default this macro is defined + * and size checking is enabled. By changing the project settings and + * undefining this macro size checking is eliminated and the functions + * run a bit faster. With size checking disabled the functions always + * return ARM_MATH_SUCCESS. + */ + +/** + * @defgroup groupTransforms Transform Functions + */ + +/** + * @defgroup groupController Controller Functions + */ + +/** + * @defgroup groupStats Statistics Functions + */ + +/** + * @defgroup groupSupport Support Functions + */ + +/** + * @defgroup groupInterpolation Interpolation Functions + * These functions perform 1- and 2-dimensional interpolation of data. + * Linear interpolation is used for 1-dimensional data and + * bilinear interpolation is used for 2-dimensional data. + */ + +/** + * @defgroup groupExamples Examples + */ + +/** + * @defgroup groupSVM SVM Functions + * This set of functions is implementing SVM classification on 2 classes. + * The training must be done from scikit-learn. The parameters can be easily + * generated from the scikit-learn object. Some examples are given in + * DSP/Testing/PatternGeneration/SVM.py + * + * If more than 2 classes are needed, the functions in this folder + * will have to be used, as building blocks, to do multi-class classification. + * + * No multi-class classification is provided in this SVM folder. + * + */ + + +/** + * @defgroup groupBayes Bayesian estimators + * + * Implement the naive gaussian Bayes estimator. + * The training must be done from scikit-learn. + * + * The parameters can be easily + * generated from the scikit-learn object. Some examples are given in + * DSP/Testing/PatternGeneration/Bayes.py + */ + +/** + * @defgroup groupDistance Distance functions + * + * Distance functions for use with clustering algorithms. + * There are distance functions for float vectors and boolean vectors. + * + */ + + +#ifndef _ARM_MATH_H +#define _ARM_MATH_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* Compiler specific diagnostic adjustment */ +#if defined ( __CC_ARM ) + +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + +#elif defined ( __GNUC__ ) + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wsign-conversion" + #pragma GCC diagnostic ignored "-Wconversion" + #pragma GCC diagnostic ignored "-Wunused-parameter" + +#elif defined ( __ICCARM__ ) + +#elif defined ( __TI_ARM__ ) + +#elif defined ( __CSMC__ ) + +#elif defined ( __TASKING__ ) + +#elif defined ( _MSC_VER ) + +#else + #error Unknown compiler +#endif + + +/* Included for instrinsics definitions */ +#if defined (_MSC_VER ) +#include +#define __STATIC_FORCEINLINE static __forceinline +#define __STATIC_INLINE static __inline +#define __ALIGNED(x) __declspec(align(x)) + +#elif defined (__GNUC_PYTHON__) +#include +#define __ALIGNED(x) __attribute__((aligned(x))) +#define __STATIC_FORCEINLINE static __attribute__((inline)) +#define __STATIC_INLINE static __attribute__((inline)) +#pragma GCC diagnostic ignored "-Wunused-function" +#pragma GCC diagnostic ignored "-Wattributes" + +#else +#include "cmsis_compiler.h" +#endif + + + +#include +#include +#include +#include + + +#define F64_MAX ((float64_t)DBL_MAX) +#define F32_MAX ((float32_t)FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_MAX ((float16_t)FLT_MAX) +#endif + +#define F64_MIN (-DBL_MAX) +#define F32_MIN (-FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_MIN (-(float16_t)FLT_MAX) +#endif + +#define F64_ABSMAX ((float64_t)DBL_MAX) +#define F32_ABSMAX ((float32_t)FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_ABSMAX ((float16_t)FLT_MAX) +#endif + +#define F64_ABSMIN ((float64_t)0.0) +#define F32_ABSMIN ((float32_t)0.0) + +#if defined(ARM_MATH_FLOAT16) +#define F16_ABSMIN ((float16_t)0.0) +#endif + +#define Q31_MAX ((q31_t)(0x7FFFFFFFL)) +#define Q15_MAX ((q15_t)(0x7FFF)) +#define Q7_MAX ((q7_t)(0x7F)) +#define Q31_MIN ((q31_t)(0x80000000L)) +#define Q15_MIN ((q15_t)(0x8000)) +#define Q7_MIN ((q7_t)(0x80)) + +#define Q31_ABSMAX ((q31_t)(0x7FFFFFFFL)) +#define Q15_ABSMAX ((q15_t)(0x7FFF)) +#define Q7_ABSMAX ((q7_t)(0x7F)) +#define Q31_ABSMIN ((q31_t)0) +#define Q15_ABSMIN ((q15_t)0) +#define Q7_ABSMIN ((q7_t)0) + +/* evaluate ARM DSP feature */ +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + #define ARM_MATH_DSP 1 +#endif + +#if defined(ARM_MATH_NEON) +#include +#endif + +#if defined (ARM_MATH_HELIUM) + #define ARM_MATH_MVEF + #define ARM_MATH_FLOAT16 +#endif + +#if defined (ARM_MATH_MVEF) + #define ARM_MATH_MVEI + #define ARM_MATH_FLOAT16 +#endif + +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) +#include +#endif + + + /** + * @brief Macros required for reciprocal calculation in Normalized LMS + */ + +#define DELTA_Q31 ((q31_t)(0x100)) +#define DELTA_Q15 ((q15_t)0x5) +#define INDEX_MASK 0x0000003F +#ifndef PI + #define PI 3.14159265358979f +#endif + + /** + * @brief Macros required for SINE and COSINE Fast math approximations + */ + +#define FAST_MATH_TABLE_SIZE 512 +#define FAST_MATH_Q31_SHIFT (32 - 10) +#define FAST_MATH_Q15_SHIFT (16 - 10) +#define CONTROLLER_Q31_SHIFT (32 - 9) +#define TABLE_SPACING_Q31 0x400000 +#define TABLE_SPACING_Q15 0x80 + + /** + * @brief Macros required for SINE and COSINE Controller functions + */ + /* 1.31(q31) Fixed value of 2/360 */ + /* -1 to +1 is divided into 360 values so total spacing is (2/360) */ +#define INPUT_SPACING 0xB60B61 + + /** + * @brief Macros for complex numbers + */ + + /* Dimension C vector space */ + #define CMPLX_DIM 2 + + /** + * @brief Error status returned by some functions in the library. + */ + + typedef enum + { + ARM_MATH_SUCCESS = 0, /**< No error */ + ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */ + ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */ + ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation */ + ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */ + ARM_MATH_SINGULAR = -5, /**< Input matrix is singular and cannot be inverted */ + ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */ + } arm_status; + + /** + * @brief 8-bit fractional data type in 1.7 format. + */ + typedef int8_t q7_t; + + /** + * @brief 16-bit fractional data type in 1.15 format. + */ + typedef int16_t q15_t; + + /** + * @brief 32-bit fractional data type in 1.31 format. + */ + typedef int32_t q31_t; + + /** + * @brief 64-bit fractional data type in 1.63 format. + */ + typedef int64_t q63_t; + + /** + * @brief 32-bit floating-point type definition. + */ + typedef float float32_t; + + /** + * @brief 64-bit floating-point type definition. + */ + typedef double float64_t; + + /** + * @brief vector types + */ +#if defined(ARM_MATH_NEON) || defined (ARM_MATH_MVEI) + /** + * @brief 64-bit fractional 128-bit vector data type in 1.63 format + */ + typedef int64x2_t q63x2_t; + + /** + * @brief 32-bit fractional 128-bit vector data type in 1.31 format. + */ + typedef int32x4_t q31x4_t; + + /** + * @brief 16-bit fractional 128-bit vector data type with 16-bit alignement in 1.15 format. + */ + typedef __ALIGNED(2) int16x8_t q15x8_t; + + /** + * @brief 8-bit fractional 128-bit vector data type with 8-bit alignement in 1.7 format. + */ + typedef __ALIGNED(1) int8x16_t q7x16_t; + + /** + * @brief 32-bit fractional 128-bit vector pair data type in 1.31 format. + */ + typedef int32x4x2_t q31x4x2_t; + + /** + * @brief 32-bit fractional 128-bit vector quadruplet data type in 1.31 format. + */ + typedef int32x4x4_t q31x4x4_t; + + /** + * @brief 16-bit fractional 128-bit vector pair data type in 1.15 format. + */ + typedef int16x8x2_t q15x8x2_t; + + /** + * @brief 16-bit fractional 128-bit vector quadruplet data type in 1.15 format. + */ + typedef int16x8x4_t q15x8x4_t; + + /** + * @brief 8-bit fractional 128-bit vector pair data type in 1.7 format. + */ + typedef int8x16x2_t q7x16x2_t; + + /** + * @brief 8-bit fractional 128-bit vector quadruplet data type in 1.7 format. + */ + typedef int8x16x4_t q7x16x4_t; + + /** + * @brief 32-bit fractional data type in 9.23 format. + */ + typedef int32_t q23_t; + + /** + * @brief 32-bit fractional 128-bit vector data type in 9.23 format. + */ + typedef int32x4_t q23x4_t; + + /** + * @brief 64-bit status 128-bit vector data type. + */ + typedef int64x2_t status64x2_t; + + /** + * @brief 32-bit status 128-bit vector data type. + */ + typedef int32x4_t status32x4_t; + + /** + * @brief 16-bit status 128-bit vector data type. + */ + typedef int16x8_t status16x8_t; + + /** + * @brief 8-bit status 128-bit vector data type. + */ + typedef int8x16_t status8x16_t; + + +#endif + +#if defined(ARM_MATH_NEON) || defined(ARM_MATH_MVEF) /* floating point vector*/ + /** + * @brief 32-bit floating-point 128-bit vector type + */ + typedef float32x4_t f32x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector data type + */ + typedef __ALIGNED(2) float16x8_t f16x8_t; +#endif + + /** + * @brief 32-bit floating-point 128-bit vector pair data type + */ + typedef float32x4x2_t f32x4x2_t; + + /** + * @brief 32-bit floating-point 128-bit vector quadruplet data type + */ + typedef float32x4x4_t f32x4x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector pair data type + */ + typedef float16x8x2_t f16x8x2_t; + + /** + * @brief 16-bit floating-point 128-bit vector quadruplet data type + */ + typedef float16x8x4_t f16x8x4_t; +#endif + + /** + * @brief 32-bit ubiquitous 128-bit vector data type + */ + typedef union _any32x4_t + { + float32x4_t f; + int32x4_t i; + } any32x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit ubiquitous 128-bit vector data type + */ + typedef union _any16x8_t + { + float16x8_t f; + int16x8_t i; + } any16x8_t; +#endif + +#endif + +#if defined(ARM_MATH_NEON) + /** + * @brief 32-bit fractional 64-bit vector data type in 1.31 format. + */ + typedef int32x2_t q31x2_t; + + /** + * @brief 16-bit fractional 64-bit vector data type in 1.15 format. + */ + typedef __ALIGNED(2) int16x4_t q15x4_t; + + /** + * @brief 8-bit fractional 64-bit vector data type in 1.7 format. + */ + typedef __ALIGNED(1) int8x8_t q7x8_t; + + /** + * @brief 32-bit float 64-bit vector data type. + */ + typedef float32x2_t f32x2_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit float 64-bit vector data type. + */ + typedef __ALIGNED(2) float16x4_t f16x4_t; +#endif + + /** + * @brief 32-bit floating-point 128-bit vector triplet data type + */ + typedef float32x4x3_t f32x4x3_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector triplet data type + */ + typedef float16x8x3_t f16x8x3_t; +#endif + + /** + * @brief 32-bit fractional 128-bit vector triplet data type in 1.31 format + */ + typedef int32x4x3_t q31x4x3_t; + + /** + * @brief 16-bit fractional 128-bit vector triplet data type in 1.15 format + */ + typedef int16x8x3_t q15x8x3_t; + + /** + * @brief 8-bit fractional 128-bit vector triplet data type in 1.7 format + */ + typedef int8x16x3_t q7x16x3_t; + + /** + * @brief 32-bit floating-point 64-bit vector pair data type + */ + typedef float32x2x2_t f32x2x2_t; + + /** + * @brief 32-bit floating-point 64-bit vector triplet data type + */ + typedef float32x2x3_t f32x2x3_t; + + /** + * @brief 32-bit floating-point 64-bit vector quadruplet data type + */ + typedef float32x2x4_t f32x2x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 64-bit vector pair data type + */ + typedef float16x4x2_t f16x4x2_t; + + /** + * @brief 16-bit floating-point 64-bit vector triplet data type + */ + typedef float16x4x3_t f16x4x3_t; + + /** + * @brief 16-bit floating-point 64-bit vector quadruplet data type + */ + typedef float16x4x4_t f16x4x4_t; +#endif + + /** + * @brief 32-bit fractional 64-bit vector pair data type in 1.31 format + */ + typedef int32x2x2_t q31x2x2_t; + + /** + * @brief 32-bit fractional 64-bit vector triplet data type in 1.31 format + */ + typedef int32x2x3_t q31x2x3_t; + + /** + * @brief 32-bit fractional 64-bit vector quadruplet data type in 1.31 format + */ + typedef int32x4x3_t q31x2x4_t; + + /** + * @brief 16-bit fractional 64-bit vector pair data type in 1.15 format + */ + typedef int16x4x2_t q15x4x2_t; + + /** + * @brief 16-bit fractional 64-bit vector triplet data type in 1.15 format + */ + typedef int16x4x2_t q15x4x3_t; + + /** + * @brief 16-bit fractional 64-bit vector quadruplet data type in 1.15 format + */ + typedef int16x4x3_t q15x4x4_t; + + /** + * @brief 8-bit fractional 64-bit vector pair data type in 1.7 format + */ + typedef int8x8x2_t q7x8x2_t; + + /** + * @brief 8-bit fractional 64-bit vector triplet data type in 1.7 format + */ + typedef int8x8x3_t q7x8x3_t; + + /** + * @brief 8-bit fractional 64-bit vector quadruplet data type in 1.7 format + */ + typedef int8x8x4_t q7x8x4_t; + + /** + * @brief 32-bit ubiquitous 64-bit vector data type + */ + typedef union _any32x2_t + { + float32x2_t f; + int32x2_t i; + } any32x2_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit ubiquitous 64-bit vector data type + */ + typedef union _any16x4_t + { + float16x4_t f; + int16x4_t i; + } any16x4_t; +#endif + + /** + * @brief 32-bit status 64-bit vector data type. + */ + typedef int32x4_t status32x2_t; + + /** + * @brief 16-bit status 64-bit vector data type. + */ + typedef int16x8_t status16x4_t; + + /** + * @brief 8-bit status 64-bit vector data type. + */ + typedef int8x16_t status8x8_t; + +#endif + + + +/** + @brief definition to read/write two 16 bit values. + @deprecated + */ +#if defined ( __CC_ARM ) + #define __SIMD32_TYPE int32_t __packed +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + #define __SIMD32_TYPE int32_t +#elif defined ( __GNUC__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __ICCARM__ ) + #define __SIMD32_TYPE int32_t __packed +#elif defined ( __TI_ARM__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __CSMC__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __TASKING__ ) + #define __SIMD32_TYPE __un(aligned) int32_t +#elif defined(_MSC_VER ) + #define __SIMD32_TYPE int32_t +#else + #error Unknown compiler +#endif + +#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) +#define __SIMD32_CONST(addr) ( (__SIMD32_TYPE * ) (addr)) +#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE * ) (addr)) +#define __SIMD64(addr) (*( int64_t **) & (addr)) + +#define STEP(x) (x) <= 0 ? 0 : 1 +#define SQ(x) ((x) * (x)) + +/* SIMD replacement */ + + +/** + @brief Read 2 Q15 from Q15 pointer. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2 ( + q15_t * pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, pQ15, 4); +#else + val = (pQ15[1] << 16) | (pQ15[0] & 0x0FFFF) ; +#endif + + return (val); +} + +/** + @brief Read 2 Q15 from Q15 pointer and increment pointer afterwards. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2_ia ( + q15_t ** pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ15, 4); +#else + val = ((*pQ15)[1] << 16) | ((*pQ15)[0] & 0x0FFFF); +#endif + + *pQ15 += 2; + return (val); +} + +/** + @brief Read 2 Q15 from Q15 pointer and decrement pointer afterwards. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2_da ( + q15_t ** pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ15, 4); +#else + val = ((*pQ15)[1] << 16) | ((*pQ15)[0] & 0x0FFFF); +#endif + + *pQ15 -= 2; + return (val); +} + +/** + @brief Write 2 Q15 to Q15 pointer and increment pointer afterwards. + @param[in] pQ15 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q15x2_ia ( + q15_t ** pQ15, + q31_t value) +{ + q31_t val = value; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (*pQ15, &val, 4); +#else + (*pQ15)[0] = (val & 0x0FFFF); + (*pQ15)[1] = (val >> 16) & 0x0FFFF; +#endif + + *pQ15 += 2; +} + +/** + @brief Write 2 Q15 to Q15 pointer. + @param[in] pQ15 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q15x2 ( + q15_t * pQ15, + q31_t value) +{ + q31_t val = value; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (pQ15, &val, 4); +#else + pQ15[0] = val & 0x0FFFF; + pQ15[1] = val >> 16; +#endif +} + + +/** + @brief Read 4 Q7 from Q7 pointer and increment pointer afterwards. + @param[in] pQ7 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q7x4_ia ( + q7_t ** pQ7) +{ + q31_t val; + + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ7, 4); +#else + val =(((*pQ7)[3] & 0x0FF) << 24) | (((*pQ7)[2] & 0x0FF) << 16) | (((*pQ7)[1] & 0x0FF) << 8) | ((*pQ7)[0] & 0x0FF); +#endif + + *pQ7 += 4; + + return (val); +} + +/** + @brief Read 4 Q7 from Q7 pointer and decrement pointer afterwards. + @param[in] pQ7 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q7x4_da ( + q7_t ** pQ7) +{ + q31_t val; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ7, 4); +#else + val = ((((*pQ7)[3]) & 0x0FF) << 24) | ((((*pQ7)[2]) & 0x0FF) << 16) | ((((*pQ7)[1]) & 0x0FF) << 8) | ((*pQ7)[0] & 0x0FF); +#endif + *pQ7 -= 4; + + return (val); +} + +/** + @brief Write 4 Q7 to Q7 pointer and increment pointer afterwards. + @param[in] pQ7 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q7x4_ia ( + q7_t ** pQ7, + q31_t value) +{ + q31_t val = value; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (*pQ7, &val, 4); +#else + (*pQ7)[0] = val & 0x0FF; + (*pQ7)[1] = (val >> 8) & 0x0FF; + (*pQ7)[2] = (val >> 16) & 0x0FF; + (*pQ7)[3] = (val >> 24) & 0x0FF; + +#endif + *pQ7 += 4; +} + +/* + +Normally those kind of definitions are in a compiler file +in Core or Core_A. + +But for MSVC compiler it is a bit special. The goal is very specific +to CMSIS-DSP and only to allow the use of this library from other +systems like Python or Matlab. + +MSVC is not going to be used to cross-compile to ARM. So, having a MSVC +compiler file in Core or Core_A would not make sense. + +*/ +#if defined ( _MSC_VER ) || defined(__GNUC_PYTHON__) + __STATIC_FORCEINLINE uint8_t __CLZ(uint32_t data) + { + if (data == 0U) { return 32U; } + + uint32_t count = 0U; + uint32_t mask = 0x80000000U; + + while ((data & mask) == 0U) + { + count += 1U; + mask = mask >> 1U; + } + return count; + } + + __STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) + { + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; + } + + __STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) + { + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; + } +#endif + +#ifndef ARM_MATH_DSP + /** + * @brief definition to pack two 16 bit values. + */ + #define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \ + (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) ) + #define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \ + (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) ) +#endif + + /** + * @brief definition to pack four 8 bit values. + */ +#ifndef ARM_MATH_BIG_ENDIAN + #define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v3) << 24) & (int32_t)0xFF000000) ) +#else + #define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v0) << 24) & (int32_t)0xFF000000) ) +#endif + + + /** + * @brief Clips Q63 to Q31 values. + */ + __STATIC_FORCEINLINE q31_t clip_q63_to_q31( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x; + } + + /** + * @brief Clips Q63 to Q15 values. + */ + __STATIC_FORCEINLINE q15_t clip_q63_to_q15( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15); + } + + /** + * @brief Clips Q31 to Q7 values. + */ + __STATIC_FORCEINLINE q7_t clip_q31_to_q7( + q31_t x) + { + return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? + ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x; + } + + /** + * @brief Clips Q31 to Q15 values. + */ + __STATIC_FORCEINLINE q15_t clip_q31_to_q15( + q31_t x) + { + return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? + ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x; + } + + /** + * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. + */ + __STATIC_FORCEINLINE q63_t mult32x64( + q63_t x, + q31_t y) + { + return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) + + (((q63_t) (x >> 32) * y) ) ); + } + + /** + * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type. + */ + __STATIC_FORCEINLINE uint32_t arm_recip_q31( + q31_t in, + q31_t * dst, + const q31_t * pRecipTable) + { + q31_t out; + uint32_t tempVal; + uint32_t index, i; + uint32_t signBits; + + if (in > 0) + { + signBits = ((uint32_t) (__CLZ( in) - 1)); + } + else + { + signBits = ((uint32_t) (__CLZ(-in) - 1)); + } + + /* Convert input sample to 1.31 format */ + in = (in << signBits); + + /* calculation of index for initial approximated Val */ + index = (uint32_t)(in >> 24); + index = (index & INDEX_MASK); + + /* 1.31 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0U; i < 2U; i++) + { + tempVal = (uint32_t) (((q63_t) in * out) >> 31); + tempVal = 0x7FFFFFFFu - tempVal; + /* 1.31 with exp 1 */ + /* out = (q31_t) (((q63_t) out * tempVal) >> 30); */ + out = clip_q63_to_q31(((q63_t) out * tempVal) >> 30); + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1U); + } + + + /** + * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type. + */ + __STATIC_FORCEINLINE uint32_t arm_recip_q15( + q15_t in, + q15_t * dst, + const q15_t * pRecipTable) + { + q15_t out = 0; + uint32_t tempVal = 0; + uint32_t index = 0, i = 0; + uint32_t signBits = 0; + + if (in > 0) + { + signBits = ((uint32_t)(__CLZ( in) - 17)); + } + else + { + signBits = ((uint32_t)(__CLZ(-in) - 17)); + } + + /* Convert input sample to 1.15 format */ + in = (in << signBits); + + /* calculation of index for initial approximated Val */ + index = (uint32_t)(in >> 8); + index = (index & INDEX_MASK); + + /* 1.15 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0U; i < 2U; i++) + { + tempVal = (uint32_t) (((q31_t) in * out) >> 15); + tempVal = 0x7FFFu - tempVal; + /* 1.15 with exp 1 */ + out = (q15_t) (((q31_t) out * tempVal) >> 14); + /* out = clip_q31_to_q15(((q31_t) out * tempVal) >> 14); */ + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1); + } + +/** + * @brief Integer exponentiation + * @param[in] x value + * @param[in] nb integer exponent >= 1 + * @return x^nb + * + */ +__STATIC_INLINE float32_t arm_exponent_f32(float32_t x, int32_t nb) +{ + float32_t r = x; + nb --; + while(nb > 0) + { + r = r * x; + nb--; + } + return(r); +} + +/** + * @brief 64-bit to 32-bit unsigned normalization + * @param[in] in is input unsigned long long value + * @param[out] normalized is the 32-bit normalized value + * @param[out] norm is norm scale + */ +__STATIC_INLINE void arm_norm_64_to_32u(uint64_t in, int32_t * normalized, int32_t *norm) +{ + int32_t n1; + int32_t hi = (int32_t) (in >> 32); + int32_t lo = (int32_t) ((in << 32) >> 32); + + n1 = __CLZ(hi) - 32; + if (!n1) + { + /* + * input fits in 32-bit + */ + n1 = __CLZ(lo); + if (!n1) + { + /* + * MSB set, need to scale down by 1 + */ + *norm = -1; + *normalized = (((uint32_t) lo) >> 1); + } else + { + if (n1 == 32) + { + /* + * input is zero + */ + *norm = 0; + *normalized = 0; + } else + { + /* + * 32-bit normalization + */ + *norm = n1 - 1; + *normalized = lo << *norm; + } + } + } else + { + /* + * input fits in 64-bit + */ + n1 = 1 - n1; + *norm = -n1; + /* + * 64 bit normalization + */ + *normalized = (((uint32_t) lo) >> n1) | (hi << (32 - n1)); + } +} + +__STATIC_INLINE q31_t arm_div_q63_to_q31(q63_t num, q31_t den) +{ + q31_t result; + uint64_t absNum; + int32_t normalized; + int32_t norm; + + /* + * if sum fits in 32bits + * avoid costly 64-bit division + */ + absNum = num > 0 ? num : -num; + arm_norm_64_to_32u(absNum, &normalized, &norm); + if (norm > 0) + /* + * 32-bit division + */ + result = (q31_t) num / den; + else + /* + * 64-bit division + */ + result = (q31_t) (num / den); + + return result; +} + + +/* + * @brief C custom defined intrinsic functions + */ +#if !defined (ARM_MATH_DSP) + + /* + * @brief C custom defined QADD8 + */ + __STATIC_FORCEINLINE uint32_t __QADD8( + uint32_t x, + uint32_t y) + { + q31_t r, s, t, u; + + r = __SSAT(((((q31_t)x << 24) >> 24) + (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; + s = __SSAT(((((q31_t)x << 16) >> 24) + (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; + t = __SSAT(((((q31_t)x << 8) >> 24) + (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; + u = __SSAT(((((q31_t)x ) >> 24) + (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; + + return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); + } + + + /* + * @brief C custom defined QSUB8 + */ + __STATIC_FORCEINLINE uint32_t __QSUB8( + uint32_t x, + uint32_t y) + { + q31_t r, s, t, u; + + r = __SSAT(((((q31_t)x << 24) >> 24) - (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; + s = __SSAT(((((q31_t)x << 16) >> 24) - (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; + t = __SSAT(((((q31_t)x << 8) >> 24) - (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; + u = __SSAT(((((q31_t)x ) >> 24) - (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; + + return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); + } + + + /* + * @brief C custom defined QADD16 + */ + __STATIC_FORCEINLINE uint32_t __QADD16( + uint32_t x, + uint32_t y) + { +/* q31_t r, s; without initialisation 'arm_offset_q15 test' fails but 'intrinsic' tests pass! for armCC */ + q31_t r = 0, s = 0; + + r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHADD16 + */ + __STATIC_FORCEINLINE uint32_t __SHADD16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QSUB16 + */ + __STATIC_FORCEINLINE uint32_t __QSUB16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHSUB16 + */ + __STATIC_FORCEINLINE uint32_t __SHSUB16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QASX + */ + __STATIC_FORCEINLINE uint32_t __QASX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHASX + */ + __STATIC_FORCEINLINE uint32_t __SHASX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QSAX + */ + __STATIC_FORCEINLINE uint32_t __QSAX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHSAX + */ + __STATIC_FORCEINLINE uint32_t __SHSAX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SMUSDX + */ + __STATIC_FORCEINLINE uint32_t __SMUSDX( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); + } + + /* + * @brief C custom defined SMUADX + */ + __STATIC_FORCEINLINE uint32_t __SMUADX( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); + } + + + /* + * @brief C custom defined QADD + */ + __STATIC_FORCEINLINE int32_t __QADD( + int32_t x, + int32_t y) + { + return ((int32_t)(clip_q63_to_q31((q63_t)x + (q31_t)y))); + } + + + /* + * @brief C custom defined QSUB + */ + __STATIC_FORCEINLINE int32_t __QSUB( + int32_t x, + int32_t y) + { + return ((int32_t)(clip_q63_to_q31((q63_t)x - (q31_t)y))); + } + + + /* + * @brief C custom defined SMLAD + */ + __STATIC_FORCEINLINE uint32_t __SMLAD( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLADX + */ + __STATIC_FORCEINLINE uint32_t __SMLADX( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLSDX + */ + __STATIC_FORCEINLINE uint32_t __SMLSDX( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLALD + */ + __STATIC_FORCEINLINE uint64_t __SMLALD( + uint32_t x, + uint32_t y, + uint64_t sum) + { +/* return (sum + ((q15_t) (x >> 16) * (q15_t) (y >> 16)) + ((q15_t) x * (q15_t) y)); */ + return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + + ( ((q63_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLALDX + */ + __STATIC_FORCEINLINE uint64_t __SMLALDX( + uint32_t x, + uint32_t y, + uint64_t sum) + { +/* return (sum + ((q15_t) (x >> 16) * (q15_t) y)) + ((q15_t) x * (q15_t) (y >> 16)); */ + return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q63_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMUAD + */ + __STATIC_FORCEINLINE uint32_t __SMUAD( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); + } + + + /* + * @brief C custom defined SMUSD + */ + __STATIC_FORCEINLINE uint32_t __SMUSD( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); + } + + + /* + * @brief C custom defined SXTB16 + */ + __STATIC_FORCEINLINE uint32_t __SXTB16( + uint32_t x) + { + return ((uint32_t)(((((q31_t)x << 24) >> 24) & (q31_t)0x0000FFFF) | + ((((q31_t)x << 8) >> 8) & (q31_t)0xFFFF0000) )); + } + + /* + * @brief C custom defined SMMLA + */ + __STATIC_FORCEINLINE int32_t __SMMLA( + int32_t x, + int32_t y, + int32_t sum) + { + return (sum + (int32_t) (((int64_t) x * y) >> 32)); + } + +#endif /* !defined (ARM_MATH_DSP) */ + + + /** + * @brief Instance structure for the Q7 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q7; + + /** + * @brief Instance structure for the Q15 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_f32; + + /** + * @brief Processing function for the Q7 FIR filter. + * @param[in] S points to an instance of the Q7 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q7( + const arm_fir_instance_q7 * S, + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q7 FIR filter. + * @param[in,out] S points to an instance of the Q7 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed. + */ + void arm_fir_init_q7( + arm_fir_instance_q7 * S, + uint16_t numTaps, + const q7_t * pCoeffs, + q7_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q15 FIR filter. + * @param[in] S points to an instance of the Q15 FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q15( + const arm_fir_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q15 FIR filter (fast version). + * @param[in] S points to an instance of the Q15 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_fast_q15( + const arm_fir_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 FIR filter. + * @param[in,out] S points to an instance of the Q15 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + * @return The function returns either + * ARM_MATH_SUCCESS if initialization was successful or + * ARM_MATH_ARGUMENT_ERROR if numTaps is not a supported value. + */ + arm_status arm_fir_init_q15( + arm_fir_instance_q15 * S, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR filter. + * @param[in] S points to an instance of the Q31 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q31( + const arm_fir_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q31 FIR filter (fast version). + * @param[in] S points to an instance of the Q31 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_fast_q31( + const arm_fir_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 FIR filter. + * @param[in,out] S points to an instance of the Q31 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + */ + void arm_fir_init_q31( + arm_fir_instance_q31 * S, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the floating-point FIR filter. + * @param[in] S points to an instance of the floating-point FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_f32( + const arm_fir_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point FIR filter. + * @param[in,out] S points to an instance of the floating-point FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + */ + void arm_fir_init_f32( + arm_fir_instance_f32 * S, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + /** + * @brief Instance structure for the Q15 Biquad cascade filter. + */ + typedef struct + { + int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + } arm_biquad_casd_df1_inst_q15; + + /** + * @brief Instance structure for the Q31 Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + } arm_biquad_casd_df1_inst_q31; + + /** + * @brief Instance structure for the floating-point Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_casd_df1_inst_f32; + +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + /** + * @brief Instance structure for the modified Biquad coefs required by vectorized code. + */ + typedef struct + { + float32_t coeffs[8][4]; /**< Points to the array of modified coefficients. The array is of length 32. There is one per stage */ + } arm_biquad_mod_coef_f32; +#endif + + /** + * @brief Processing function for the Q15 Biquad cascade filter. + * @param[in] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_q15( + const arm_biquad_casd_df1_inst_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 Biquad cascade filter. + * @param[in,out] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cascade_df1_init_q15( + arm_biquad_casd_df1_inst_q15 * S, + uint8_t numStages, + const q15_t * pCoeffs, + q15_t * pState, + int8_t postShift); + + /** + * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_fast_q15( + const arm_biquad_casd_df1_inst_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 Biquad cascade filter + * @param[in] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_q31( + const arm_biquad_casd_df1_inst_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_fast_q31( + const arm_biquad_casd_df1_inst_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 Biquad cascade filter. + * @param[in,out] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cascade_df1_init_q31( + arm_biquad_casd_df1_inst_q31 * S, + uint8_t numStages, + const q31_t * pCoeffs, + q31_t * pState, + int8_t postShift); + + /** + * @brief Processing function for the floating-point Biquad cascade filter. + * @param[in] S points to an instance of the floating-point Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_f32( + const arm_biquad_casd_df1_inst_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point Biquad cascade filter. + * @param[in,out] S points to an instance of the floating-point Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pCoeffsMod points to the modified filter coefficients (only MVE version). + * @param[in] pState points to the state buffer. + */ +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + void arm_biquad_cascade_df1_mve_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + arm_biquad_mod_coef_f32 * pCoeffsMod, + float32_t * pState); +#endif + + void arm_biquad_cascade_df1_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u16( + const uint16_t * pSrc, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u32( + const uint32_t * pSrc, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u8( + const uint8_t * pSrc, + uint8_t * pDst, + uint32_t blockSize); + +/** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Struct for specifying sorting algorithm + */ + typedef enum + { + ARM_SORT_BITONIC = 0, + /**< Bitonic sort */ + ARM_SORT_BUBBLE = 1, + /**< Bubble sort */ + ARM_SORT_HEAP = 2, + /**< Heap sort */ + ARM_SORT_INSERTION = 3, + /**< Insertion sort */ + ARM_SORT_QUICK = 4, + /**< Quick sort */ + ARM_SORT_SELECTION = 5 + /**< Selection sort */ + } arm_sort_alg; + + /** + * @brief Struct for specifying sorting algorithm + */ + typedef enum + { + ARM_SORT_DESCENDING = 0, + /**< Descending order (9 to 0) */ + ARM_SORT_ASCENDING = 1 + /**< Ascending order (0 to 9) */ + } arm_sort_dir; + + /** + * @brief Instance structure for the sorting algorithms. + */ + typedef struct + { + arm_sort_alg alg; /**< Sorting algorithm selected */ + arm_sort_dir dir; /**< Sorting order (direction) */ + } arm_sort_instance_f32; + + /** + * @param[in] S points to an instance of the sorting structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_sort_f32( + const arm_sort_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @param[in,out] S points to an instance of the sorting structure. + * @param[in] alg Selected algorithm. + * @param[in] dir Sorting order. + */ + void arm_sort_init_f32( + arm_sort_instance_f32 * S, + arm_sort_alg alg, + arm_sort_dir dir); + + /** + * @brief Instance structure for the sorting algorithms. + */ + typedef struct + { + arm_sort_dir dir; /**< Sorting order (direction) */ + float32_t * buffer; /**< Working buffer */ + } arm_merge_sort_instance_f32; + + /** + * @param[in] S points to an instance of the sorting structure. + * @param[in,out] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_merge_sort_f32( + const arm_merge_sort_instance_f32 * S, + float32_t *pSrc, + float32_t *pDst, + uint32_t blockSize); + + /** + * @param[in,out] S points to an instance of the sorting structure. + * @param[in] dir Sorting order. + * @param[in] buffer Working buffer. + */ + void arm_merge_sort_init_f32( + arm_merge_sort_instance_f32 * S, + arm_sort_dir dir, + float32_t * buffer); + + /** + * @brief Struct for specifying cubic spline type + */ + typedef enum + { + ARM_SPLINE_NATURAL = 0, /**< Natural spline */ + ARM_SPLINE_PARABOLIC_RUNOUT = 1 /**< Parabolic runout spline */ + } arm_spline_type; + + /** + * @brief Instance structure for the floating-point cubic spline interpolation. + */ + typedef struct + { + arm_spline_type type; /**< Type (boundary conditions) */ + const float32_t * x; /**< x values */ + const float32_t * y; /**< y values */ + uint32_t n_x; /**< Number of known data points */ + float32_t * coeffs; /**< Coefficients buffer (b,c, and d) */ + } arm_spline_instance_f32; + + /** + * @brief Processing function for the floating-point cubic spline interpolation. + * @param[in] S points to an instance of the floating-point spline structure. + * @param[in] xq points to the x values ot the interpolated data points. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples of output data. + */ + void arm_spline_f32( + arm_spline_instance_f32 * S, + const float32_t * xq, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point cubic spline interpolation. + * @param[in,out] S points to an instance of the floating-point spline structure. + * @param[in] type type of cubic spline interpolation (boundary conditions) + * @param[in] x points to the x values of the known data points. + * @param[in] y points to the y values of the known data points. + * @param[in] n number of known data points. + * @param[in] coeffs coefficients array for b, c, and d + * @param[in] tempBuffer buffer array for internal computations + */ + void arm_spline_init_f32( + arm_spline_instance_f32 * S, + arm_spline_type type, + const float32_t * x, + const float32_t * y, + uint32_t n, + float32_t * coeffs, + float32_t * tempBuffer); + + /** + * @brief Instance structure for the floating-point matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + float32_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_f32; + + /** + * @brief Instance structure for the floating-point matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + float64_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_f64; + + /** + * @brief Instance structure for the Q15 matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q15_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_q15; + + /** + * @brief Instance structure for the Q31 matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q31_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_q31; + + /** + * @brief Floating-point matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pScratch); + + /** + * @brief Q31, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_f32( + const arm_matrix_instance_f32 * pSrc, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_q15( + const arm_matrix_instance_q15 * pSrc, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_q31( + const arm_matrix_instance_q31 * pSrc, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @param[in] pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @param[in] pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_fast_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q31 matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_fast_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix scaling. + * @param[in] pSrc points to the input matrix + * @param[in] scale scale factor + * @param[out] pDst points to the output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_f32( + const arm_matrix_instance_f32 * pSrc, + float32_t scale, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix scaling. + * @param[in] pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_q15( + const arm_matrix_instance_q15 * pSrc, + q15_t scaleFract, + int32_t shift, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix scaling. + * @param[in] pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_q31( + const arm_matrix_instance_q31 * pSrc, + q31_t scaleFract, + int32_t shift, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Q31 matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_q31( + arm_matrix_instance_q31 * S, + uint16_t nRows, + uint16_t nColumns, + q31_t * pData); + + /** + * @brief Q15 matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_q15( + arm_matrix_instance_q15 * S, + uint16_t nRows, + uint16_t nColumns, + q15_t * pData); + + /** + * @brief Floating-point matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_f32( + arm_matrix_instance_f32 * S, + uint16_t nRows, + uint16_t nColumns, + float32_t * pData); + + + /** + * @brief Instance structure for the Q15 PID Control. + */ + typedef struct + { + q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ +#if !defined (ARM_MATH_DSP) + q15_t A1; + q15_t A2; +#else + q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/ +#endif + q15_t state[3]; /**< The state array of length 3. */ + q15_t Kp; /**< The proportional gain. */ + q15_t Ki; /**< The integral gain. */ + q15_t Kd; /**< The derivative gain. */ + } arm_pid_instance_q15; + + /** + * @brief Instance structure for the Q31 PID Control. + */ + typedef struct + { + q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + q31_t A2; /**< The derived gain, A2 = Kd . */ + q31_t state[3]; /**< The state array of length 3. */ + q31_t Kp; /**< The proportional gain. */ + q31_t Ki; /**< The integral gain. */ + q31_t Kd; /**< The derivative gain. */ + } arm_pid_instance_q31; + + /** + * @brief Instance structure for the floating-point PID Control. + */ + typedef struct + { + float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + float32_t A2; /**< The derived gain, A2 = Kd . */ + float32_t state[3]; /**< The state array of length 3. */ + float32_t Kp; /**< The proportional gain. */ + float32_t Ki; /**< The integral gain. */ + float32_t Kd; /**< The derivative gain. */ + } arm_pid_instance_f32; + + + + /** + * @brief Initialization function for the floating-point PID Control. + * @param[in,out] S points to an instance of the PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_f32( + arm_pid_instance_f32 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the floating-point PID Control. + * @param[in,out] S is an instance of the floating-point PID Control structure + */ + void arm_pid_reset_f32( + arm_pid_instance_f32 * S); + + + /** + * @brief Initialization function for the Q31 PID Control. + * @param[in,out] S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_q31( + arm_pid_instance_q31 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the Q31 PID Control. + * @param[in,out] S points to an instance of the Q31 PID Control structure + */ + + void arm_pid_reset_q31( + arm_pid_instance_q31 * S); + + + /** + * @brief Initialization function for the Q15 PID Control. + * @param[in,out] S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_q15( + arm_pid_instance_q15 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the Q15 PID Control. + * @param[in,out] S points to an instance of the q15 PID Control structure + */ + void arm_pid_reset_q15( + arm_pid_instance_q15 * S); + + + /** + * @brief Instance structure for the floating-point Linear Interpolate function. + */ + typedef struct + { + uint32_t nValues; /**< nValues */ + float32_t x1; /**< x1 */ + float32_t xSpacing; /**< xSpacing */ + float32_t *pYData; /**< pointer to the table of Y values */ + } arm_linear_interp_instance_f32; + + /** + * @brief Instance structure for the floating-point bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + float32_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_f32; + + /** + * @brief Instance structure for the Q31 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q31_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q31; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q15_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q15; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q7_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q7; + + + /** + * @brief Q7 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix2_instance_q15; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_q15( + arm_cfft_radix2_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_q15( + const arm_cfft_radix2_instance_q15 * S, + q15_t * pSrc); + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q15_t *pTwiddle; /**< points to the twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q15; + +/* Deprecated */ + arm_status arm_cfft_radix4_init_q15( + arm_cfft_radix4_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix4_q15( + const arm_cfft_radix4_instance_q15 * S, + q15_t * pSrc); + + /** + * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix2_instance_q31; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_q31( + arm_cfft_radix2_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_q31( + const arm_cfft_radix2_instance_q31 * S, + q31_t * pSrc); + + /** + * @brief Instance structure for the Q31 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q31_t *pTwiddle; /**< points to the twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q31; + +/* Deprecated */ + void arm_cfft_radix4_q31( + const arm_cfft_radix4_instance_q31 * S, + q31_t * pSrc); + +/* Deprecated */ + arm_status arm_cfft_radix4_init_q31( + arm_cfft_radix4_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix2_instance_f32; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_f32( + arm_cfft_radix2_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_f32( + const arm_cfft_radix2_instance_f32 * S, + float32_t * pSrc); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix4_instance_f32; + +/* Deprecated */ + arm_status arm_cfft_radix4_init_f32( + arm_cfft_radix4_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix4_f32( + const arm_cfft_radix4_instance_f32 * S, + float32_t * pSrc); + + /** + * @brief Instance structure for the fixed-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const q15_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEI) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const q15_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const q15_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const q15_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_q15; + +arm_status arm_cfft_init_q15( + arm_cfft_instance_q15 * S, + uint16_t fftLen); + +void arm_cfft_q15( + const arm_cfft_instance_q15 * S, + q15_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the fixed-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEI) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const q31_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const q31_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const q31_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_q31; + +arm_status arm_cfft_init_q31( + arm_cfft_instance_q31 * S, + uint16_t fftLen); + +void arm_cfft_q31( + const arm_cfft_instance_q31 * S, + q31_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const float32_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const float32_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const float32_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_f32; + + + arm_status arm_cfft_init_f32( + arm_cfft_instance_f32 * S, + uint16_t fftLen); + + void arm_cfft_f32( + const arm_cfft_instance_f32 * S, + float32_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + + /** + * @brief Instance structure for the Double Precision Floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const float64_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ + } arm_cfft_instance_f64; + + void arm_cfft_f64( + const arm_cfft_instance_f64 * S, + float64_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the Q15 RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ +#if defined(ARM_MATH_MVEI) + arm_cfft_instance_q15 cfftInst; +#else + const arm_cfft_instance_q15 *pCfft; /**< points to the complex FFT instance. */ +#endif + } arm_rfft_instance_q15; + + arm_status arm_rfft_init_q15( + arm_rfft_instance_q15 * S, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q15( + const arm_rfft_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst); + + /** + * @brief Instance structure for the Q31 RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ +#if defined(ARM_MATH_MVEI) + arm_cfft_instance_q31 cfftInst; +#else + const arm_cfft_instance_q31 *pCfft; /**< points to the complex FFT instance. */ +#endif + } arm_rfft_instance_q31; + + arm_status arm_rfft_init_q31( + arm_rfft_instance_q31 * S, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q31( + const arm_rfft_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst); + + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint16_t fftLenBy2; /**< length of the complex FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_rfft_instance_f32; + + arm_status arm_rfft_init_f32( + arm_rfft_instance_f32 * S, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_f32( + const arm_rfft_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst); + + /** + * @brief Instance structure for the Double Precision Floating-point RFFT/RIFFT function. + */ +typedef struct + { + arm_cfft_instance_f64 Sint; /**< Internal CFFT structure. */ + uint16_t fftLenRFFT; /**< length of the real sequence */ + const float64_t * pTwiddleRFFT; /**< Twiddle factors real stage */ + } arm_rfft_fast_instance_f64 ; + +arm_status arm_rfft_fast_init_f64 ( + arm_rfft_fast_instance_f64 * S, + uint16_t fftLen); + + +void arm_rfft_fast_f64( + arm_rfft_fast_instance_f64 * S, + float64_t * p, float64_t * pOut, + uint8_t ifftFlag); + + + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ +typedef struct + { + arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */ + uint16_t fftLenRFFT; /**< length of the real sequence */ + const float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */ + } arm_rfft_fast_instance_f32 ; + +arm_status arm_rfft_fast_init_f32 ( + arm_rfft_fast_instance_f32 * S, + uint16_t fftLen); + + + void arm_rfft_fast_f32( + const arm_rfft_fast_instance_f32 * S, + float32_t * p, float32_t * pOut, + uint8_t ifftFlag); + + /** + * @brief Instance structure for the floating-point DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + float32_t normalize; /**< normalizing factor. */ + const float32_t *pTwiddle; /**< points to the twiddle factor table. */ + const float32_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_f32; + + + /** + * @brief Initialization function for the floating-point DCT4/IDCT4. + * @param[in,out] S points to an instance of floating-point DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of floating-point RFFT/RIFFT structure. + * @param[in] S_CFFT points to an instance of floating-point CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. + */ + arm_status arm_dct4_init_f32( + arm_dct4_instance_f32 * S, + arm_rfft_instance_f32 * S_RFFT, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint16_t N, + uint16_t Nby2, + float32_t normalize); + + + /** + * @brief Processing function for the floating-point DCT4/IDCT4. + * @param[in] S points to an instance of the floating-point DCT4/IDCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_f32( + const arm_dct4_instance_f32 * S, + float32_t * pState, + float32_t * pInlineBuffer); + + + /** + * @brief Instance structure for the Q31 DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q31_t normalize; /**< normalizing factor. */ + const q31_t *pTwiddle; /**< points to the twiddle factor table. */ + const q31_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q31; + + + /** + * @brief Initialization function for the Q31 DCT4/IDCT4. + * @param[in,out] S points to an instance of Q31 DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of Q31 RFFT/RIFFT structure + * @param[in] S_CFFT points to an instance of Q31 CFFT/CIFFT structure + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + arm_status arm_dct4_init_q31( + arm_dct4_instance_q31 * S, + arm_rfft_instance_q31 * S_RFFT, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q31_t normalize); + + + /** + * @brief Processing function for the Q31 DCT4/IDCT4. + * @param[in] S points to an instance of the Q31 DCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_q31( + const arm_dct4_instance_q31 * S, + q31_t * pState, + q31_t * pInlineBuffer); + + + /** + * @brief Instance structure for the Q15 DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q15_t normalize; /**< normalizing factor. */ + const q15_t *pTwiddle; /**< points to the twiddle factor table. */ + const q15_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q15; + + + /** + * @brief Initialization function for the Q15 DCT4/IDCT4. + * @param[in,out] S points to an instance of Q15 DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of Q15 RFFT/RIFFT structure. + * @param[in] S_CFFT points to an instance of Q15 CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + arm_status arm_dct4_init_q15( + arm_dct4_instance_q15 * S, + arm_rfft_instance_q15 * S_RFFT, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q15_t normalize); + + + /** + * @brief Processing function for the Q15 DCT4/IDCT4. + * @param[in] S points to an instance of the Q15 DCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_q15( + const arm_dct4_instance_q15 * S, + q15_t * pState, + q15_t * pInlineBuffer); + + + /** + * @brief Floating-point vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a floating-point vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scale scale factor to be applied + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_f32( + const float32_t * pSrc, + float32_t scale, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q7 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q7( + const q7_t * pSrc, + q7_t scaleFract, + int8_t shift, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q15 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q15( + const q15_t * pSrc, + q15_t scaleFract, + int8_t shift, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q31 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q31( + const q31_t * pSrc, + q31_t scaleFract, + int8_t shift, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Dot product of floating-point vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t blockSize, + float32_t * result); + + + /** + * @brief Dot product of Q7 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + uint32_t blockSize, + q31_t * result); + + + /** + * @brief Dot product of Q15 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + + /** + * @brief Dot product of Q31 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + + /** + * @brief Shifts the elements of a Q7 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q7( + const q7_t * pSrc, + int8_t shiftBits, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Shifts the elements of a Q15 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q15( + const q15_t * pSrc, + int8_t shiftBits, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Shifts the elements of a Q31 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q31( + const q31_t * pSrc, + int8_t shiftBits, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a floating-point vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_f32( + const float32_t * pSrc, + float32_t offset, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q7 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q7( + const q7_t * pSrc, + q7_t offset, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q15 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q15( + const q15_t * pSrc, + q15_t offset, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q31 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q31( + const q31_t * pSrc, + q31_t offset, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a floating-point vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q7 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q15 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q31 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a floating-point vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q7 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q15 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q31 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a floating-point vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_f32( + float32_t value, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q7 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q7( + q7_t value, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q15 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q15( + q15_t value, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q31 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q31( + q31_t value, + q31_t * pDst, + uint32_t blockSize); + + +/** + * @brief Convolution of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + */ + void arm_conv_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + + + /** + * @brief Convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + */ + void arm_conv_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + +/** + * @brief Convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + */ + void arm_conv_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + + /** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + + /** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + */ + void arm_conv_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Convolution of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + */ + void arm_conv_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + + /** + * @brief Partial convolution of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Partial convolution of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q7 sequences + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + +/** + * @brief Partial convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Instance structure for the Q15 FIR decimator. + */ + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR decimator. + */ + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_q31; + +/** + @brief Instance structure for floating-point FIR decimator. + */ +typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_f32; + + +/** + @brief Processing function for floating-point FIR decimator. + @param[in] S points to an instance of the floating-point FIR decimator structure + @param[in] pSrc points to the block of input data + @param[out] pDst points to the block of output data + @param[in] blockSize number of samples to process + */ +void arm_fir_decimate_f32( + const arm_fir_decimate_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + +/** + @brief Initialization function for the floating-point FIR decimator. + @param[in,out] S points to an instance of the floating-point FIR decimator structure + @param[in] numTaps number of coefficients in the filter + @param[in] M decimation factor + @param[in] pCoeffs points to the filter coefficients + @param[in] pState points to the state buffer + @param[in] blockSize number of input samples to process per call + @return execution status + - \ref ARM_MATH_SUCCESS : Operation successful + - \ref ARM_MATH_LENGTH_ERROR : blockSize is not a multiple of M + */ +arm_status arm_fir_decimate_init_f32( + arm_fir_decimate_instance_f32 * S, + uint16_t numTaps, + uint8_t M, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 FIR decimator. + * @param[in] S points to an instance of the Q15 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_q15( + const arm_fir_decimate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q15 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_fast_q15( + const arm_fir_decimate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 FIR decimator. + * @param[in,out] S points to an instance of the Q15 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + arm_status arm_fir_decimate_init_q15( + arm_fir_decimate_instance_q15 * S, + uint16_t numTaps, + uint8_t M, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 FIR decimator. + * @param[in] S points to an instance of the Q31 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_q31( + const arm_fir_decimate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q31 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_fast_q31( + const arm_fir_decimate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR decimator. + * @param[in,out] S points to an instance of the Q31 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + arm_status arm_fir_decimate_init_q31( + arm_fir_decimate_instance_q31 * S, + uint16_t numTaps, + uint8_t M, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */ + } arm_fir_interpolate_instance_f32; + + + /** + * @brief Processing function for the Q15 FIR interpolator. + * @param[in] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_q15( + const arm_fir_interpolate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 FIR interpolator. + * @param[in,out] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_q15( + arm_fir_interpolate_instance_q15 * S, + uint8_t L, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 FIR interpolator. + * @param[in] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_q31( + const arm_fir_interpolate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR interpolator. + * @param[in,out] S points to an instance of the Q31 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_q31( + arm_fir_interpolate_instance_q31 * S, + uint8_t L, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point FIR interpolator. + * @param[in] S points to an instance of the floating-point FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_f32( + const arm_fir_interpolate_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point FIR interpolator. + * @param[in,out] S points to an instance of the floating-point FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_f32( + arm_fir_interpolate_instance_f32 * S, + uint8_t L, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the high precision Q31 Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ + const q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */ + } arm_biquad_cas_df1_32x64_ins_q31; + + + /** + * @param[in] S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cas_df1_32x64_q31( + const arm_biquad_cas_df1_32x64_ins_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @param[in,out] S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cas_df1_32x64_init_q31( + arm_biquad_cas_df1_32x64_ins_q31 * S, + uint8_t numStages, + const q31_t * pCoeffs, + q63_t * pState, + uint8_t postShift); + + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ + const float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_df2T_instance_f32; + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ + const float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_stereo_df2T_instance_f32; + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float64_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ + const float64_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_df2T_instance_f64; + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df2T_f32( + const arm_biquad_cascade_df2T_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. 2 channels + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_stereo_df2T_f32( + const arm_biquad_cascade_stereo_df2T_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df2T_f64( + const arm_biquad_cascade_df2T_instance_f64 * S, + const float64_t * pSrc, + float64_t * pDst, + uint32_t blockSize); + + +#if defined(ARM_MATH_NEON) +void arm_biquad_cascade_df2T_compute_coefs_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + float32_t * pCoeffs); +#endif + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_df2T_init_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_stereo_df2T_init_f32( + arm_biquad_cascade_stereo_df2T_instance_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_df2T_init_f64( + arm_biquad_cascade_df2T_instance_f64 * S, + uint8_t numStages, + const float64_t * pCoeffs, + float64_t * pState); + + + /** + * @brief Instance structure for the Q15 FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_f32; + + + /** + * @brief Initialization function for the Q15 FIR lattice filter. + * @param[in] S points to an instance of the Q15 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_q15( + arm_fir_lattice_instance_q15 * S, + uint16_t numStages, + const q15_t * pCoeffs, + q15_t * pState); + + + /** + * @brief Processing function for the Q15 FIR lattice filter. + * @param[in] S points to an instance of the Q15 FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_q15( + const arm_fir_lattice_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR lattice filter. + * @param[in] S points to an instance of the Q31 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_q31( + arm_fir_lattice_instance_q31 * S, + uint16_t numStages, + const q31_t * pCoeffs, + q31_t * pState); + + + /** + * @brief Processing function for the Q31 FIR lattice filter. + * @param[in] S points to an instance of the Q31 FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_q31( + const arm_fir_lattice_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + +/** + * @brief Initialization function for the floating-point FIR lattice filter. + * @param[in] S points to an instance of the floating-point FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_f32( + arm_fir_lattice_instance_f32 * S, + uint16_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Processing function for the floating-point FIR lattice filter. + * @param[in] S points to an instance of the floating-point FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_f32( + const arm_fir_lattice_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_f32; + + + /** + * @brief Processing function for the floating-point IIR lattice filter. + * @param[in] S points to an instance of the floating-point IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_f32( + const arm_iir_lattice_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point IIR lattice filter. + * @param[in] S points to an instance of the floating-point IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to the state buffer. The array is of length numStages+blockSize-1. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_init_f32( + arm_iir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t * pkCoeffs, + float32_t * pvCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 IIR lattice filter. + * @param[in] S points to an instance of the Q31 IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_q31( + const arm_iir_lattice_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 IIR lattice filter. + * @param[in] S points to an instance of the Q31 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to the state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_init_q31( + arm_iir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t * pkCoeffs, + q31_t * pvCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 IIR lattice filter. + * @param[in] S points to an instance of the Q15 IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_q15( + const arm_iir_lattice_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + +/** + * @brief Initialization function for the Q15 IIR lattice filter. + * @param[in] S points to an instance of the fixed-point Q15 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process per call. + */ + void arm_iir_lattice_init_q15( + arm_iir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t * pkCoeffs, + q15_t * pvCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the floating-point LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that controls filter coefficient updates. */ + } arm_lms_instance_f32; + + + /** + * @brief Processing function for floating-point LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_f32( + const arm_lms_instance_f32 * S, + const float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for floating-point LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to the coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_init_f32( + arm_lms_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + } arm_lms_instance_q15; + + + /** + * @brief Initialization function for the Q15 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to the coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_init_q15( + arm_lms_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint32_t postShift); + + + /** + * @brief Processing function for Q15 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_q15( + const arm_lms_instance_q15 * S, + const q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + } arm_lms_instance_q31; + + + /** + * @brief Processing function for Q31 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_q31( + const arm_lms_instance_q31 * S, + const q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q31 LMS filter. + * @param[in] S points to an instance of the Q31 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_init_q31( + arm_lms_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint32_t postShift); + + + /** + * @brief Instance structure for the floating-point normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that control filter coefficient updates. */ + float32_t energy; /**< saves previous frame energy. */ + float32_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_f32; + + + /** + * @brief Processing function for floating-point normalized LMS filter. + * @param[in] S points to an instance of the floating-point normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_f32( + arm_lms_norm_instance_f32 * S, + const float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for floating-point normalized LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_init_f32( + arm_lms_norm_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + const q31_t *recipTable; /**< points to the reciprocal initial value table. */ + q31_t energy; /**< saves previous frame energy. */ + q31_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q31; + + + /** + * @brief Processing function for Q31 normalized LMS filter. + * @param[in] S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_q31( + arm_lms_norm_instance_q31 * S, + const q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q31 normalized LMS filter. + * @param[in] S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_norm_init_q31( + arm_lms_norm_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint8_t postShift); + + + /** + * @brief Instance structure for the Q15 normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< Number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + const q15_t *recipTable; /**< Points to the reciprocal initial value table. */ + q15_t energy; /**< saves previous frame energy. */ + q15_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q15; + + + /** + * @brief Processing function for Q15 normalized LMS filter. + * @param[in] S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_q15( + arm_lms_norm_instance_q15 * S, + const q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q15 normalized LMS filter. + * @param[in] S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_norm_init_q15( + arm_lms_norm_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint8_t postShift); + + + /** + * @brief Correlation of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + + +/** + @brief Correlation of Q15 sequences + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. +*/ +void arm_correlate_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch); + + +/** + @brief Correlation of Q15 sequences. + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + +/** + @brief Correlation of Q15 sequences (fast version). + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + @return none + */ +void arm_correlate_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + +/** + @brief Correlation of Q15 sequences (fast version). + @param[in] pSrcA points to the first input sequence. + @param[in] srcALen length of the first input sequence. + @param[in] pSrcB points to the second input sequence. + @param[in] srcBLen length of the second input sequence. + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + */ +void arm_correlate_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch); + + + /** + * @brief Correlation of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + +/** + @brief Correlation of Q31 sequences (fast version). + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ +void arm_correlate_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Correlation of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + */ + void arm_correlate_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Correlation of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + + /** + * @brief Instance structure for the floating-point sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_f32; + + /** + * @brief Instance structure for the Q31 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q31; + + /** + * @brief Instance structure for the Q15 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q15; + + /** + * @brief Instance structure for the Q7 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q7; + + + /** + * @brief Processing function for the floating-point sparse FIR filter. + * @param[in] S points to an instance of the floating-point sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_f32( + arm_fir_sparse_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + float32_t * pScratchIn, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point sparse FIR filter. + * @param[in,out] S points to an instance of the floating-point sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_f32( + arm_fir_sparse_instance_f32 * S, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 sparse FIR filter. + * @param[in] S points to an instance of the Q31 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q31( + arm_fir_sparse_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + q31_t * pScratchIn, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 sparse FIR filter. + * @param[in,out] S points to an instance of the Q31 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q31( + arm_fir_sparse_instance_q31 * S, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 sparse FIR filter. + * @param[in] S points to an instance of the Q15 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q15( + arm_fir_sparse_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + q15_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 sparse FIR filter. + * @param[in,out] S points to an instance of the Q15 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q15( + arm_fir_sparse_instance_q15 * S, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q7 sparse FIR filter. + * @param[in] S points to an instance of the Q7 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q7( + arm_fir_sparse_instance_q7 * S, + const q7_t * pSrc, + q7_t * pDst, + q7_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q7 sparse FIR filter. + * @param[in,out] S points to an instance of the Q7 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q7( + arm_fir_sparse_instance_q7 * S, + uint16_t numTaps, + const q7_t * pCoeffs, + q7_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Floating-point sin_cos function. + * @param[in] theta input value in degrees + * @param[out] pSinVal points to the processed sine output. + * @param[out] pCosVal points to the processed cos output. + */ + void arm_sin_cos_f32( + float32_t theta, + float32_t * pSinVal, + float32_t * pCosVal); + + + /** + * @brief Q31 sin_cos function. + * @param[in] theta scaled input value in degrees + * @param[out] pSinVal points to the processed sine output. + * @param[out] pCosVal points to the processed cosine output. + */ + void arm_sin_cos_q31( + q31_t theta, + q31_t * pSinVal, + q31_t * pCosVal); + + + /** + * @brief Floating-point complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @ingroup groupController + */ + + /** + * @defgroup PID PID Motor Control + * + * A Proportional Integral Derivative (PID) controller is a generic feedback control + * loop mechanism widely used in industrial control systems. + * A PID controller is the most commonly used type of feedback controller. + * + * This set of functions implements (PID) controllers + * for Q15, Q31, and floating-point data types. The functions operate on a single sample + * of data and each call to the function returns a single processed value. + * S points to an instance of the PID control data structure. in + * is the input sample value. The functions return the output value. + * + * \par Algorithm: + *
+   *    y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
+   *    A0 = Kp + Ki + Kd
+   *    A1 = (-Kp ) - (2 * Kd )
+   *    A2 = Kd
+   * 
+ * + * \par + * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant + * + * \par + * \image html PID.gif "Proportional Integral Derivative Controller" + * + * \par + * The PID controller calculates an "error" value as the difference between + * the measured output and the reference input. + * The controller attempts to minimize the error by adjusting the process control inputs. + * The proportional value determines the reaction to the current error, + * the integral value determines the reaction based on the sum of recent errors, + * and the derivative value determines the reaction based on the rate at which the error has been changing. + * + * \par Instance Structure + * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. + * A separate instance structure must be defined for each PID Controller. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Reset Functions + * There is also an associated reset function for each data type which clears the state array. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. + * - Zeros out the values in the state buffer. + * + * \par + * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the PID Controller functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup PID + * @{ + */ + + /** + * @brief Process function for the floating-point PID Control. + * @param[in,out] S is an instance of the floating-point PID Control structure + * @param[in] in input sample to process + * @return processed output sample. + */ + __STATIC_FORCEINLINE float32_t arm_pid_f32( + arm_pid_instance_f32 * S, + float32_t in) + { + float32_t out; + + /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */ + out = (S->A0 * in) + + (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + + } + +/** + @brief Process function for the Q31 PID Control. + @param[in,out] S points to an instance of the Q31 PID Control structure + @param[in] in input sample to process + @return processed output sample. + + \par Scaling and Overflow Behavior + The function is implemented using an internal 64-bit accumulator. + The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + Thus, if the accumulator result overflows it wraps around rather than clip. + In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. + After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + */ +__STATIC_FORCEINLINE q31_t arm_pid_q31( + arm_pid_instance_q31 * S, + q31_t in) + { + q63_t acc; + q31_t out; + + /* acc = A0 * x[n] */ + acc = (q63_t) S->A0 * in; + + /* acc += A1 * x[n-1] */ + acc += (q63_t) S->A1 * S->state[0]; + + /* acc += A2 * x[n-2] */ + acc += (q63_t) S->A2 * S->state[1]; + + /* convert output to 1.31 format to add y[n-1] */ + out = (q31_t) (acc >> 31U); + + /* out += y[n-1] */ + out += S->state[2]; + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + } + + +/** + @brief Process function for the Q15 PID Control. + @param[in,out] S points to an instance of the Q15 PID Control structure + @param[in] in input sample to process + @return processed output sample. + + \par Scaling and Overflow Behavior + The function is implemented using a 64-bit internal accumulator. + Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + Lastly, the accumulator is saturated to yield a result in 1.15 format. + */ +__STATIC_FORCEINLINE q15_t arm_pid_q15( + arm_pid_instance_q15 * S, + q15_t in) + { + q63_t acc; + q15_t out; + +#if defined (ARM_MATH_DSP) + /* Implementation of PID controller */ + + /* acc = A0 * x[n] */ + acc = (q31_t) __SMUAD((uint32_t)S->A0, (uint32_t)in); + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc = (q63_t)__SMLALD((uint32_t)S->A1, (uint32_t)read_q15x2 (S->state), (uint64_t)acc); +#else + /* acc = A0 * x[n] */ + acc = ((q31_t) S->A0) * in; + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc += (q31_t) S->A1 * S->state[0]; + acc += (q31_t) S->A2 * S->state[1]; +#endif + + /* acc += y[n-1] */ + acc += (q31_t) S->state[2] << 15; + + /* saturate the output */ + out = (q15_t) (__SSAT((q31_t)(acc >> 15), 16)); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + } + + /** + * @} end of PID group + */ + + + /** + * @brief Floating-point matrix inverse. + * @param[in] src points to the instance of the input floating-point matrix structure. + * @param[out] dst points to the instance of the output floating-point matrix structure. + * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. + * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. + */ + arm_status arm_mat_inverse_f32( + const arm_matrix_instance_f32 * src, + arm_matrix_instance_f32 * dst); + + + /** + * @brief Floating-point matrix inverse. + * @param[in] src points to the instance of the input floating-point matrix structure. + * @param[out] dst points to the instance of the output floating-point matrix structure. + * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. + * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. + */ + arm_status arm_mat_inverse_f64( + const arm_matrix_instance_f64 * src, + arm_matrix_instance_f64 * dst); + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup clarke Vector Clarke Transform + * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector. + * Generally the Clarke transform uses three-phase currents Ia, Ib and Ic to calculate currents + * in the two-phase orthogonal stator axis Ialpha and Ibeta. + * When Ialpha is superposed with Ia as shown in the figure below + * \image html clarke.gif Stator current space vector and its components in (a,b). + * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta + * can be calculated using only Ia and Ib. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeFormula.gif + * where Ia and Ib are the instantaneous stator phases and + * pIalpha and pIbeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup clarke + * @{ + */ + + /** + * + * @brief Floating-point Clarke transform + * @param[in] Ia input three-phase coordinate a + * @param[in] Ib input three-phase coordinate b + * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] pIbeta points to output two-phase orthogonal vector axis beta + * @return none + */ + __STATIC_FORCEINLINE void arm_clarke_f32( + float32_t Ia, + float32_t Ib, + float32_t * pIalpha, + float32_t * pIbeta) + { + /* Calculate pIalpha using the equation, pIalpha = Ia */ + *pIalpha = Ia; + + /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */ + *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib); + } + + +/** + @brief Clarke transform for Q31 version + @param[in] Ia input three-phase coordinate a + @param[in] Ib input three-phase coordinate b + @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + @param[out] pIbeta points to output two-phase orthogonal vector axis beta + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_clarke_q31( + q31_t Ia, + q31_t Ib, + q31_t * pIalpha, + q31_t * pIbeta) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIalpha from Ia by equation pIalpha = Ia */ + *pIalpha = Ia; + + /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30); + + /* Intermediate product is calculated by (2/sqrt(3) * Ib) */ + product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30); + + /* pIbeta is calculated by adding the intermediate products */ + *pIbeta = __QADD(product1, product2); + } + + /** + * @} end of clarke group + */ + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_clarke Vector Inverse Clarke Transform + * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeInvFormula.gif + * where pIa and pIb are the instantaneous stator phases and + * Ialpha and Ibeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_clarke + * @{ + */ + + /** + * @brief Floating-point Inverse Clarke transform + * @param[in] Ialpha input two-phase orthogonal vector axis alpha + * @param[in] Ibeta input two-phase orthogonal vector axis beta + * @param[out] pIa points to output three-phase coordinate a + * @param[out] pIb points to output three-phase coordinate b + * @return none + */ + __STATIC_FORCEINLINE void arm_inv_clarke_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pIa, + float32_t * pIb) + { + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ + *pIb = -0.5f * Ialpha + 0.8660254039f * Ibeta; + } + + +/** + @brief Inverse Clarke transform for Q31 version + @param[in] Ialpha input two-phase orthogonal vector axis alpha + @param[in] Ibeta input two-phase orthogonal vector axis beta + @param[out] pIa points to output three-phase coordinate a + @param[out] pIb points to output three-phase coordinate b + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the subtraction, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_inv_clarke_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pIa, + q31_t * pIb) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31); + + /* Intermediate product is calculated by (1/sqrt(3) * pIb) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31); + + /* pIb is calculated by subtracting the products */ + *pIb = __QSUB(product2, product1); + } + + /** + * @} end of inv_clarke group + */ + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup park Vector Park Transform + * + * Forward Park transform converts the input two-coordinate vector to flux and torque components. + * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents + * from the stationary to the moving reference frame and control the spatial relationship between + * the stator vector current and rotor flux vector. + * If we consider the d axis aligned with the rotor flux, the diagram below shows the + * current vector and the relationship from the two reference frames: + * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkFormula.gif + * where Ialpha and Ibeta are the stator vector components, + * pId and pIq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup park + * @{ + */ + + /** + * @brief Floating-point Park transform + * @param[in] Ialpha input two-phase vector coordinate alpha + * @param[in] Ibeta input two-phase vector coordinate beta + * @param[out] pId points to output rotor reference frame d + * @param[out] pIq points to output rotor reference frame q + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none + * + * The function implements the forward Park transform. + * + */ + __STATIC_FORCEINLINE void arm_park_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pId, + float32_t * pIq, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */ + *pId = Ialpha * cosVal + Ibeta * sinVal; + + /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */ + *pIq = -Ialpha * sinVal + Ibeta * cosVal; + } + + +/** + @brief Park transform for Q31 version + @param[in] Ialpha input two-phase vector coordinate alpha + @param[in] Ibeta input two-phase vector coordinate beta + @param[out] pId points to output rotor reference frame d + @param[out] pIq points to output rotor reference frame q + @param[in] sinVal sine value of rotation angle theta + @param[in] cosVal cosine value of rotation angle theta + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition and subtraction, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_park_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pId, + q31_t * pIq, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Ialpha * cosVal) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * sinVal) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Ialpha * sinVal) */ + product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * cosVal) */ + product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31); + + /* Calculate pId by adding the two intermediate products 1 and 2 */ + *pId = __QADD(product1, product2); + + /* Calculate pIq by subtracting the two intermediate products 3 from 4 */ + *pIq = __QSUB(product4, product3); + } + + /** + * @} end of park group + */ + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_park Vector Inverse Park transform + * Inverse Park transform converts the input flux and torque components to two-coordinate vector. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkInvFormula.gif + * where pIalpha and pIbeta are the stator vector components, + * Id and Iq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_park + * @{ + */ + + /** + * @brief Floating-point Inverse Park transform + * @param[in] Id input coordinate of rotor reference frame d + * @param[in] Iq input coordinate of rotor reference frame q + * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] pIbeta points to output two-phase orthogonal vector axis beta + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none + */ + __STATIC_FORCEINLINE void arm_inv_park_f32( + float32_t Id, + float32_t Iq, + float32_t * pIalpha, + float32_t * pIbeta, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */ + *pIalpha = Id * cosVal - Iq * sinVal; + + /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */ + *pIbeta = Id * sinVal + Iq * cosVal; + } + + +/** + @brief Inverse Park transform for Q31 version + @param[in] Id input coordinate of rotor reference frame d + @param[in] Iq input coordinate of rotor reference frame q + @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + @param[out] pIbeta points to output two-phase orthogonal vector axis beta + @param[in] sinVal sine value of rotation angle theta + @param[in] cosVal cosine value of rotation angle theta + @return none + + @par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_inv_park_q31( + q31_t Id, + q31_t Iq, + q31_t * pIalpha, + q31_t * pIbeta, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Id * cosVal) */ + product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Iq * sinVal) */ + product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Id * sinVal) */ + product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Iq * cosVal) */ + product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31); + + /* Calculate pIalpha by using the two intermediate products 1 and 2 */ + *pIalpha = __QSUB(product1, product2); + + /* Calculate pIbeta by using the two intermediate products 3 and 4 */ + *pIbeta = __QADD(product4, product3); + } + + /** + * @} end of Inverse park group + */ + + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup LinearInterpolate Linear Interpolation + * + * Linear interpolation is a method of curve fitting using linear polynomials. + * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line + * + * \par + * \image html LinearInterp.gif "Linear interpolation" + * + * \par + * A Linear Interpolate function calculates an output value(y), for the input(x) + * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values) + * + * \par Algorithm: + *
+   *       y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
+   *       where x0, x1 are nearest values of input x
+   *             y0, y1 are nearest values to output y
+   * 
+ * + * \par + * This set of functions implements Linear interpolation process + * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single + * sample of data and each call to the function returns a single processed value. + * S points to an instance of the Linear Interpolate function data structure. + * x is the input sample value. The functions returns the output value. + * + * \par + * if x is outside of the table boundary, Linear interpolation returns first value of the table + * if x is below input range and returns last value of table if x is above range. + */ + + /** + * @addtogroup LinearInterpolate + * @{ + */ + + /** + * @brief Process function for the floating-point Linear Interpolation Function. + * @param[in,out] S is an instance of the floating-point Linear Interpolation structure + * @param[in] x input sample to process + * @return y processed output sample. + * + */ + __STATIC_FORCEINLINE float32_t arm_linear_interp_f32( + arm_linear_interp_instance_f32 * S, + float32_t x) + { + float32_t y; + float32_t x0, x1; /* Nearest input values */ + float32_t y0, y1; /* Nearest output values */ + float32_t xSpacing = S->xSpacing; /* spacing between input values */ + int32_t i; /* Index variable */ + float32_t *pYData = S->pYData; /* pointer to output table */ + + /* Calculation of index */ + i = (int32_t) ((x - S->x1) / xSpacing); + + if (i < 0) + { + /* Iniatilize output for below specified range as least output value of table */ + y = pYData[0]; + } + else if ((uint32_t)i >= (S->nValues - 1)) + { + /* Iniatilize output for above specified range as last output value of table */ + y = pYData[S->nValues - 1]; + } + else + { + /* Calculation of nearest input values */ + x0 = S->x1 + i * xSpacing; + x1 = S->x1 + (i + 1) * xSpacing; + + /* Read of nearest output values */ + y0 = pYData[i]; + y1 = pYData[i + 1]; + + /* Calculation of output */ + y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0)); + + } + + /* returns output value */ + return (y); + } + + + /** + * + * @brief Process function for the Q31 Linear Interpolation Function. + * @param[in] pYData pointer to Q31 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + __STATIC_FORCEINLINE q31_t arm_linear_interp_q31( + q31_t * pYData, + q31_t x, + uint32_t nValues) + { + q31_t y; /* output */ + q31_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & (q31_t)0xFFF00000) >> 20); + + if (index >= (int32_t)(nValues - 1)) + { + return (pYData[nValues - 1]); + } + else if (index < 0) + { + return (pYData[0]); + } + else + { + /* 20 bits for the fractional part */ + /* shift left by 11 to keep fract in 1.31 format */ + fract = (x & 0x000FFFFF) << 11; + + /* Read two nearest output values from the index in 1.31(q31) format */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract) and y is in 2.30 format */ + y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32)); + + /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */ + y += ((q31_t) (((q63_t) y1 * fract) >> 32)); + + /* Convert y to 1.31 format */ + return (y << 1U); + } + } + + + /** + * + * @brief Process function for the Q15 Linear Interpolation Function. + * @param[in] pYData pointer to Q15 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + __STATIC_FORCEINLINE q15_t arm_linear_interp_q15( + q15_t * pYData, + q31_t x, + uint32_t nValues) + { + q63_t y; /* output */ + q15_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & (int32_t)0xFFF00000) >> 20); + + if (index >= (int32_t)(nValues - 1)) + { + return (pYData[nValues - 1]); + } + else if (index < 0) + { + return (pYData[0]); + } + else + { + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract) and y is in 13.35 format */ + y = ((q63_t) y0 * (0xFFFFF - fract)); + + /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */ + y += ((q63_t) y1 * (fract)); + + /* convert y to 1.15 format */ + return (q15_t) (y >> 20); + } + } + + + /** + * + * @brief Process function for the Q7 Linear Interpolation Function. + * @param[in] pYData pointer to Q7 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + */ + __STATIC_FORCEINLINE q7_t arm_linear_interp_q7( + q7_t * pYData, + q31_t x, + uint32_t nValues) + { + q31_t y; /* output */ + q7_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + uint32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + if (x < 0) + { + return (pYData[0]); + } + index = (x >> 20) & 0xfff; + + if (index >= (nValues - 1)) + { + return (pYData[nValues - 1]); + } + else + { + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index and are in 1.7(q7) format */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */ + y = ((y0 * (0xFFFFF - fract))); + + /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */ + y += (y1 * fract); + + /* convert y to 1.7(q7) format */ + return (q7_t) (y >> 20); + } + } + + /** + * @} end of LinearInterpolate group + */ + + /** + * @brief Fast approximation to the trigonometric sine function for floating-point data. + * @param[in] x input value in radians. + * @return sin(x). + */ + float32_t arm_sin_f32( + float32_t x); + + + /** + * @brief Fast approximation to the trigonometric sine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + q31_t arm_sin_q31( + q31_t x); + + + /** + * @brief Fast approximation to the trigonometric sine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + q15_t arm_sin_q15( + q15_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for floating-point data. + * @param[in] x input value in radians. + * @return cos(x). + */ + float32_t arm_cos_f32( + float32_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + q31_t arm_cos_q31( + q31_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + q15_t arm_cos_q15( + q15_t x); + + +/** + @brief Floating-point vector of log values. + @param[in] pSrc points to the input vector + @param[out] pDst points to the output vector + @param[in] blockSize number of samples in each vector + @return none + */ + void arm_vlog_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + +/** + @brief Floating-point vector of exp values. + @param[in] pSrc points to the input vector + @param[out] pDst points to the output vector + @param[in] blockSize number of samples in each vector + @return none + */ + void arm_vexp_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @ingroup groupFastMath + */ + + + /** + * @defgroup SQRT Square Root + * + * Computes the square root of a number. + * There are separate functions for Q15, Q31, and floating-point data types. + * The square root function is computed using the Newton-Raphson algorithm. + * This is an iterative algorithm of the form: + *
+   *      x1 = x0 - f(x0)/f'(x0)
+   * 
+ * where x1 is the current estimate, + * x0 is the previous estimate, and + * f'(x0) is the derivative of f() evaluated at x0. + * For the square root function, the algorithm reduces to: + *
+   *     x0 = in/2                         [initial guess]
+   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
+   * 
+ */ + + + /** + * @addtogroup SQRT + * @{ + */ + +/** + @brief Floating-point square root function. + @param[in] in input value + @param[out] pOut square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +__STATIC_FORCEINLINE arm_status arm_sqrt_f32( + float32_t in, + float32_t * pOut) + { + if (in >= 0.0f) + { +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + *pOut = __sqrtf(in); + #else + *pOut = sqrtf(in); + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + __ASM("VSQRT.F32 %0,%1" : "=t"(*pOut) : "t"(in)); + #else + *pOut = sqrtf(in); + #endif + +#else + *pOut = sqrtf(in); +#endif + + return (ARM_MATH_SUCCESS); + } + else + { + *pOut = 0.0f; + return (ARM_MATH_ARGUMENT_ERROR); + } + } + + +/** + @brief Q31 square root function. + @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF + @param[out] pOut points to square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +arm_status arm_sqrt_q31( + q31_t in, + q31_t * pOut); + + +/** + @brief Q15 square root function. + @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF + @param[out] pOut points to square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +arm_status arm_sqrt_q15( + q15_t in, + q15_t * pOut); + + /** + * @brief Vector Floating-point square root function. + * @param[in] pIn input vector. + * @param[out] pOut vector of square roots of input elements. + * @param[in] len length of input vector. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + void arm_vsqrt_f32( + float32_t * pIn, + float32_t * pOut, + uint16_t len); + + void arm_vsqrt_q31( + q31_t * pIn, + q31_t * pOut, + uint16_t len); + + void arm_vsqrt_q15( + q15_t * pIn, + q15_t * pOut, + uint16_t len); + + /** + * @} end of SQRT group + */ + + + /** + * @brief floating-point Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_f32( + int32_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const int32_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + + /** + * @brief floating-point Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_f32( + int32_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + int32_t * dst, + int32_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t rOffset; + int32_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Q15 Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_q15( + q15_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q15_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + /** + * @brief Q15 Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_q15( + q15_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q15_t * dst, + q15_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset; + q15_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update wOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Q7 Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_q7( + q7_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q7_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + /** + * @brief Q7 Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_q7( + q7_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q7_t * dst, + q7_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset; + q7_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Sum of the squares of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q31( + const q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q15( + const q15_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q7( + const q7_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Mean value of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult); + + + /** + * @brief Mean value of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Mean value of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Mean value of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Variance of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Variance of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Variance of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Standard deviation of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Standard deviation of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Standard deviation of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Floating-point complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + uint32_t numSamples, + q31_t * realResult, + q31_t * imagResult); + + + /** + * @brief Q31 complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + uint32_t numSamples, + q63_t * realResult, + q63_t * imagResult); + + + /** + * @brief Floating-point complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t numSamples, + float32_t * realResult, + float32_t * imagResult); + + + /** + * @brief Q15 complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_q15( + const q15_t * pSrcCmplx, + const q15_t * pSrcReal, + q15_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_q31( + const q31_t * pSrcCmplx, + const q31_t * pSrcReal, + q31_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_f32( + const float32_t * pSrcCmplx, + const float32_t * pSrcReal, + float32_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Minimum value of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] result is output pointer + * @param[in] index is the array index of the minimum value in the input buffer. + */ + void arm_min_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * result, + uint32_t * index); + + + /** + * @brief Minimum value of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[in] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + + + /** + * @brief Minimum value of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[out] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + + + /** + * @brief Minimum value of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[out] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q7 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q15 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q31 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a floating-point vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + + /** + @brief Maximum value of a floating-point vector. + @param[in] pSrc points to the input vector + @param[in] blockSize number of samples in input vector + @param[out] pResult maximum value returned here + @return none + */ + void arm_max_no_idx_f32( + const float32_t *pSrc, + uint32_t blockSize, + float32_t *pResult); + + /** + * @brief Q15 complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Converts the elements of the floating-point vector to Q31 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q31( + const float32_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the floating-point vector to Q15 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q15( + const float32_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the floating-point vector to Q7 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q7( + const float32_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_float( + const q31_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to Q15 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_q15( + const q31_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to Q7 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_q7( + const q31_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_float( + const q15_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q31 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_q31( + const q15_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q7 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_q7( + const q15_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q7_to_float( + const q7_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to Q31 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_q7_to_q31( + const q7_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to Q15 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_q7_to_q15( + const q7_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + +/** + * @brief Struct for specifying SVM Kernel + */ +typedef enum +{ + ARM_ML_KERNEL_LINEAR = 0, + /**< Linear kernel */ + ARM_ML_KERNEL_POLYNOMIAL = 1, + /**< Polynomial kernel */ + ARM_ML_KERNEL_RBF = 2, + /**< Radial Basis Function kernel */ + ARM_ML_KERNEL_SIGMOID = 3 + /**< Sigmoid kernel */ +} arm_ml_kernel_type; + + +/** + * @brief Instance structure for linear SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ +} arm_svm_linear_instance_f32; + + +/** + * @brief Instance structure for polynomial SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + int32_t degree; /**< Polynomial degree */ + float32_t coef0; /**< Polynomial constant */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_polynomial_instance_f32; + +/** + * @brief Instance structure for rbf SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_rbf_instance_f32; + +/** + * @brief Instance structure for sigmoid SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + float32_t coef0; /**< Independant constant */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_sigmoid_instance_f32; + +/** + * @brief SVM linear instance init function + * @param[in] S Parameters for SVM functions + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @return none. + * + */ + + +void arm_svm_linear_init_f32(arm_svm_linear_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes); + +/** + * @brief SVM linear prediction + * @param[in] S Pointer to an instance of the linear SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ + +void arm_svm_linear_predict_f32(const arm_svm_linear_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + +/** + * @brief SVM polynomial instance init function + * @param[in] S points to an instance of the polynomial SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] degree Polynomial degree + * @param[in] coef0 coeff0 (scikit-learn terminology) + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + + +void arm_svm_polynomial_init_f32(arm_svm_polynomial_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + int32_t degree, + float32_t coef0, + float32_t gamma + ); + +/** + * @brief SVM polynomial prediction + * @param[in] S Pointer to an instance of the polynomial SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ +void arm_svm_polynomial_predict_f32(const arm_svm_polynomial_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + +/** + * @brief SVM radial basis function instance init function + * @param[in] S points to an instance of the polynomial SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + +void arm_svm_rbf_init_f32(arm_svm_rbf_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + float32_t gamma + ); + +/** + * @brief SVM rbf prediction + * @param[in] S Pointer to an instance of the rbf SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult decision value + * @return none. + * + */ +void arm_svm_rbf_predict_f32(const arm_svm_rbf_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + +/** + * @brief SVM sigmoid instance init function + * @param[in] S points to an instance of the rbf SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] coef0 coeff0 (scikit-learn terminology) + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + +void arm_svm_sigmoid_init_f32(arm_svm_sigmoid_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + float32_t coef0, + float32_t gamma + ); + +/** + * @brief SVM sigmoid prediction + * @param[in] S Pointer to an instance of the rbf SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ +void arm_svm_sigmoid_predict_f32(const arm_svm_sigmoid_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + + +/** + * @brief Instance structure for Naive Gaussian Bayesian estimator. + */ +typedef struct +{ + uint32_t vectorDimension; /**< Dimension of vector space */ + uint32_t numberOfClasses; /**< Number of different classes */ + const float32_t *theta; /**< Mean values for the Gaussians */ + const float32_t *sigma; /**< Variances for the Gaussians */ + const float32_t *classPriors; /**< Class prior probabilities */ + float32_t epsilon; /**< Additive value to variances */ +} arm_gaussian_naive_bayes_instance_f32; + +/** + * @brief Naive Gaussian Bayesian Estimator + * + * @param[in] S points to a naive bayes instance structure + * @param[in] in points to the elements of the input vector. + * @param[in] pBuffer points to a buffer of length numberOfClasses + * @return The predicted class + * + */ + + +uint32_t arm_gaussian_naive_bayes_predict_f32(const arm_gaussian_naive_bayes_instance_f32 *S, + const float32_t * in, + float32_t *pBuffer); + +/** + * @brief Computation of the LogSumExp + * + * In probabilistic computations, the dynamic of the probability values can be very + * wide because they come from gaussian functions. + * To avoid underflow and overflow issues, the values are represented by their log. + * In this representation, multiplying the original exp values is easy : their logs are added. + * But adding the original exp values is requiring some special handling and it is the + * goal of the LogSumExp function. + * + * If the values are x1...xn, the function is computing: + * + * ln(exp(x1) + ... + exp(xn)) and the computation is done in such a way that + * rounding issues are minimised. + * + * The max xm of the values is extracted and the function is computing: + * xm + ln(exp(x1 - xm) + ... + exp(xn - xm)) + * + * @param[in] *in Pointer to an array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return LogSumExp + * + */ + + +float32_t arm_logsumexp_f32(const float32_t *in, uint32_t blockSize); + +/** + * @brief Dot product with log arithmetic + * + * Vectors are containing the log of the samples + * + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[in] pTmpBuffer temporary buffer of length blockSize + * @return The log of the dot product . + * + */ + + +float32_t arm_logsumexp_dot_prod_f32(const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t blockSize, + float32_t *pTmpBuffer); + +/** + * @brief Entropy + * + * @param[in] pSrcA Array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return Entropy -Sum(p ln p) + * + */ + + +float32_t arm_entropy_f32(const float32_t * pSrcA,uint32_t blockSize); + + +/** + * @brief Entropy + * + * @param[in] pSrcA Array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return Entropy -Sum(p ln p) + * + */ + + +float64_t arm_entropy_f64(const float64_t * pSrcA, uint32_t blockSize); + + +/** + * @brief Kullback-Leibler + * + * @param[in] pSrcA Pointer to an array of input values for probability distribution A. + * @param[in] pSrcB Pointer to an array of input values for probability distribution B. + * @param[in] blockSize Number of samples in the input array. + * @return Kullback-Leibler Divergence D(A || B) + * + */ +float32_t arm_kullback_leibler_f32(const float32_t * pSrcA + ,const float32_t * pSrcB + ,uint32_t blockSize); + + +/** + * @brief Kullback-Leibler + * + * @param[in] pSrcA Pointer to an array of input values for probability distribution A. + * @param[in] pSrcB Pointer to an array of input values for probability distribution B. + * @param[in] blockSize Number of samples in the input array. + * @return Kullback-Leibler Divergence D(A || B) + * + */ +float64_t arm_kullback_leibler_f64(const float64_t * pSrcA, + const float64_t * pSrcB, + uint32_t blockSize); + + +/** + * @brief Weighted sum + * + * + * @param[in] *in Array of input values. + * @param[in] *weigths Weights + * @param[in] blockSize Number of samples in the input array. + * @return Weighted sum + * + */ +float32_t arm_weighted_sum_f32(const float32_t *in + , const float32_t *weigths + , uint32_t blockSize); + + +/** + * @brief Barycenter + * + * + * @param[in] in List of vectors + * @param[in] weights Weights of the vectors + * @param[out] out Barycenter + * @param[in] nbVectors Number of vectors + * @param[in] vecDim Dimension of space (vector dimension) + * @return None + * + */ +void arm_barycenter_f32(const float32_t *in + , const float32_t *weights + , float32_t *out + , uint32_t nbVectors + , uint32_t vecDim); + +/** + * @brief Euclidean distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_euclidean_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Bray-Curtis distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_braycurtis_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Canberra distance between two vectors + * + * This function may divide by zero when samples pA[i] and pB[i] are both zero. + * The result of the computation will be correct. So the division per zero may be + * ignored. + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_canberra_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + + +/** + * @brief Chebyshev distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_chebyshev_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + + +/** + * @brief Cityblock (Manhattan) distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_cityblock_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Correlation distance between two vectors + * + * The input vectors are modified in place ! + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_correlation_distance_f32(float32_t *pA,float32_t *pB, uint32_t blockSize); + +/** + * @brief Cosine distance between two vectors + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_cosine_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Jensen-Shannon distance between two vectors + * + * This function is assuming that elements of second vector are > 0 + * and 0 only when the corresponding element of first vector is 0. + * Otherwise the result of the computation does not make sense + * and for speed reasons, the cases returning NaN or Infinity are not + * managed. + * + * When the function is computing x log (x / y) with x 0 and y 0, + * it will compute the right value (0) but a division per zero will occur + * and shoudl be ignored in client code. + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_jensenshannon_distance_f32(const float32_t *pA,const float32_t *pB,uint32_t blockSize); + +/** + * @brief Minkowski distance between two vectors + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] n Norm order (>= 2) + * @param[in] blockSize vector length + * @return distance + * + */ + + + +float32_t arm_minkowski_distance_f32(const float32_t *pA,const float32_t *pB, int32_t order, uint32_t blockSize); + +/** + * @brief Dice distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] order Distance order + * @param[in] blockSize Number of samples + * @return distance + * + */ + + +float32_t arm_dice_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Hamming distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_hamming_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Jaccard distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_jaccard_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Kulsinski distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_kulsinski_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Roger Stanimoto distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_rogerstanimoto_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Russell-Rao distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_russellrao_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Sokal-Michener distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_sokalmichener_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Sokal-Sneath distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_sokalsneath_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Yule distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_yule_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup BilinearInterpolate Bilinear Interpolation + * + * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid. + * The underlying function f(x, y) is sampled on a regular grid and the interpolation process + * determines values between the grid points. + * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension. + * Bilinear interpolation is often used in image processing to rescale images. + * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types. + * + * Algorithm + * \par + * The instance structure used by the bilinear interpolation functions describes a two dimensional data table. + * For floating-point, the instance structure is defined as: + *
+   *   typedef struct
+   *   {
+   *     uint16_t numRows;
+   *     uint16_t numCols;
+   *     float32_t *pData;
+   * } arm_bilinear_interp_instance_f32;
+   * 
+ * + * \par + * where numRows specifies the number of rows in the table; + * numCols specifies the number of columns in the table; + * and pData points to an array of size numRows*numCols values. + * The data table pTable is organized in row order and the supplied data values fall on integer indexes. + * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. + * + * \par + * Let (x, y) specify the desired interpolation point. Then define: + *
+   *     XF = floor(x)
+   *     YF = floor(y)
+   * 
+ * \par + * The interpolated output point is computed as: + *
+   *  f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
+   *           + f(XF+1, YF) * (x-XF)*(1-(y-YF))
+   *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
+   *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
+   * 
+ * Note that the coordinates (x, y) contain integer and fractional components. + * The integer components specify which portion of the table to use while the + * fractional components control the interpolation processor. + * + * \par + * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. + */ + + + /** + * @addtogroup BilinearInterpolate + * @{ + */ + + /** + * @brief Floating-point bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate. + * @param[in] Y interpolation coordinate. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE float32_t arm_bilinear_interp_f32( + const arm_bilinear_interp_instance_f32 * S, + float32_t X, + float32_t Y) + { + float32_t out; + float32_t f00, f01, f10, f11; + float32_t *pData = S->pData; + int32_t xIndex, yIndex, index; + float32_t xdiff, ydiff; + float32_t b1, b2, b3, b4; + + xIndex = (int32_t) X; + yIndex = (int32_t) Y; + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (xIndex < 0 || xIndex > (S->numCols - 2) || yIndex < 0 || yIndex > (S->numRows - 2)) + { + return (0); + } + + /* Calculation of index for two nearest points in X-direction */ + index = (xIndex ) + (yIndex ) * S->numCols; + + + /* Read two nearest points in X-direction */ + f00 = pData[index]; + f01 = pData[index + 1]; + + /* Calculation of index for two nearest points in Y-direction */ + index = (xIndex ) + (yIndex+1) * S->numCols; + + + /* Read two nearest points in Y-direction */ + f10 = pData[index]; + f11 = pData[index + 1]; + + /* Calculation of intermediate values */ + b1 = f00; + b2 = f01 - f00; + b3 = f10 - f00; + b4 = f00 - f01 - f10 + f11; + + /* Calculation of fractional part in X */ + xdiff = X - xIndex; + + /* Calculation of fractional part in Y */ + ydiff = Y - yIndex; + + /* Calculation of bi-linear interpolated output */ + out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff; + + /* return to application */ + return (out); + } + + + /** + * @brief Q31 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q31_t arm_bilinear_interp_q31( + arm_bilinear_interp_instance_q31 * S, + q31_t X, + q31_t Y) + { + q31_t out; /* Temporary output */ + q31_t acc = 0; /* output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q31_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q31_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* shift left xfract by 11 to keep 1.31 format */ + xfract = (X & 0x000FFFFF) << 11U; + + /* Read two nearest output values from the index */ + x1 = pYData[(rI) + (int32_t)nCols * (cI) ]; + x2 = pYData[(rI) + (int32_t)nCols * (cI) + 1]; + + /* 20 bits for the fractional part */ + /* shift left yfract by 11 to keep 1.31 format */ + yfract = (Y & 0x000FFFFF) << 11U; + + /* Read two nearest output values from the index */ + y1 = pYData[(rI) + (int32_t)nCols * (cI + 1) ]; + y2 = pYData[(rI) + (int32_t)nCols * (cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */ + out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32)); + acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32)); + + /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (xfract) >> 32)); + + /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y2 * (xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* Convert acc to 1.31(q31) format */ + return ((q31_t)(acc << 2)); + } + + + /** + * @brief Q15 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q15_t arm_bilinear_interp_q15( + arm_bilinear_interp_instance_q15 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q15_t x1, x2, y1, y2; /* Nearest output values */ + q31_t xfract, yfract; /* X, Y fractional parts */ + int32_t rI, cI; /* Row and column indices */ + q15_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & 0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; + x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; + y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */ + + /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */ + /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */ + out = (q31_t) (((q63_t) x1 * (0x0FFFFF - xfract)) >> 4U); + acc = ((q63_t) out * (0x0FFFFF - yfract)); + + /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) x2 * (0x0FFFFF - yfract)) >> 4U); + acc += ((q63_t) out * (xfract)); + + /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y1 * (0x0FFFFF - xfract)) >> 4U); + acc += ((q63_t) out * (yfract)); + + /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y2 * (xfract)) >> 4U); + acc += ((q63_t) out * (yfract)); + + /* acc is in 13.51 format and down shift acc by 36 times */ + /* Convert out to 1.15 format */ + return ((q15_t)(acc >> 36)); + } + + + /** + * @brief Q7 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q7_t arm_bilinear_interp_q7( + arm_bilinear_interp_instance_q7 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q7_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q7_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & (q31_t)0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; + x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & (q31_t)0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; + y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */ + out = ((x1 * (0xFFFFF - xfract))); + acc = (((q63_t) out * (0xFFFFF - yfract))); + + /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */ + out = ((x2 * (0xFFFFF - yfract))); + acc += (((q63_t) out * (xfract))); + + /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y1 * (0xFFFFF - xfract))); + acc += (((q63_t) out * (yfract))); + + /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y2 * (yfract))); + acc += (((q63_t) out * (xfract))); + + /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */ + return ((q7_t)(acc >> 40)); + } + + /** + * @} end of BilinearInterpolate group + */ + + +/* SMMLAR */ +#define multAcc_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32) + +/* SMMLSR */ +#define multSub_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32) + +/* SMMULR */ +#define mult_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32) + +/* SMMLA */ +#define multAcc_32x32_keep32(a, x, y) \ + a += (q31_t) (((q63_t) x * y) >> 32) + +/* SMMLS */ +#define multSub_32x32_keep32(a, x, y) \ + a -= (q31_t) (((q63_t) x * y) >> 32) + +/* SMMUL */ +#define mult_32x32_keep32(a, x, y) \ + a = (q31_t) (((q63_t) x * y ) >> 32) + + +#if defined ( __CC_ARM ) + /* Enter low optimization region - place directly above function definition */ + #if defined( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("push") \ + _Pragma ("O1") + #else + #define LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_EXIT \ + _Pragma ("pop") + #else + #define LOW_OPTIMIZATION_EXIT + #endif + + /* Enter low optimization region - place directly above function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + + /* Exit low optimization region - place directly after end of function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined (__ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __GNUC__ ) + #define LOW_OPTIMIZATION_ENTER \ + __attribute__(( optimize("-O1") )) + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __ICCARM__ ) + /* Enter low optimization region - place directly above function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + #else + #define LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #define LOW_OPTIMIZATION_EXIT + + /* Enter low optimization region - place directly above function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + #else + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __TI_ARM__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __CSMC__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __TASKING__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( _MSC_VER ) || defined(__GNUC_PYTHON__) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT +#endif + + + +/* Compiler specific diagnostic adjustment */ +#if defined ( __CC_ARM ) + +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + +#elif defined ( __GNUC__ ) +#pragma GCC diagnostic pop + +#elif defined ( __ICCARM__ ) + +#elif defined ( __TI_ARM__ ) + +#elif defined ( __CSMC__ ) + +#elif defined ( __TASKING__ ) + +#elif defined ( _MSC_VER ) + +#else + #error Unknown compiler +#endif + +#ifdef __cplusplus +} +#endif + + +#endif /* _ARM_MATH_H */ + +/** + * + * End of file. + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h new file mode 100644 index 0000000000..4d2c135ac6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h @@ -0,0 +1,235 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_mve_tables.h + * Description: common tables like fft twiddle factors, Bitreverse, reciprocal etc + * used for MVE implementation only + * + * $Date: 08. January 2020 + * $Revision: V1.7.0 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2020 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + #ifndef _ARM_MVE_TABLES_H + #define _ARM_MVE_TABLES_H + + #include "arm_math.h" + + + + + + +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_16) || defined(ARM_TABLE_TWIDDLECOEF_F32_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_f32[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_f32[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_f32[2]; +extern float32_t rearranged_twiddle_stride1_16_f32[8]; +extern float32_t rearranged_twiddle_stride2_16_f32[8]; +extern float32_t rearranged_twiddle_stride3_16_f32[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_64) || defined(ARM_TABLE_TWIDDLECOEF_F32_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_f32[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_f32[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_f32[3]; +extern float32_t rearranged_twiddle_stride1_64_f32[40]; +extern float32_t rearranged_twiddle_stride2_64_f32[40]; +extern float32_t rearranged_twiddle_stride3_64_f32[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_256) || defined(ARM_TABLE_TWIDDLECOEF_F32_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_f32[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_f32[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_f32[4]; +extern float32_t rearranged_twiddle_stride1_256_f32[168]; +extern float32_t rearranged_twiddle_stride2_256_f32[168]; +extern float32_t rearranged_twiddle_stride3_256_f32[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_1024) || defined(ARM_TABLE_TWIDDLECOEF_F32_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_f32[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_f32[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_f32[5]; +extern float32_t rearranged_twiddle_stride1_1024_f32[680]; +extern float32_t rearranged_twiddle_stride2_1024_f32[680]; +extern float32_t rearranged_twiddle_stride3_1024_f32[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_4096) || defined(ARM_TABLE_TWIDDLECOEF_F32_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_f32[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_f32[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_f32[6]; +extern float32_t rearranged_twiddle_stride1_4096_f32[2728]; +extern float32_t rearranged_twiddle_stride2_4096_f32[2728]; +extern float32_t rearranged_twiddle_stride3_4096_f32[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_16) || defined(ARM_TABLE_TWIDDLECOEF_Q31_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_q31[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_q31[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_q31[2]; +extern q31_t rearranged_twiddle_stride1_16_q31[8]; +extern q31_t rearranged_twiddle_stride2_16_q31[8]; +extern q31_t rearranged_twiddle_stride3_16_q31[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_64) || defined(ARM_TABLE_TWIDDLECOEF_Q31_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_q31[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_q31[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_q31[3]; +extern q31_t rearranged_twiddle_stride1_64_q31[40]; +extern q31_t rearranged_twiddle_stride2_64_q31[40]; +extern q31_t rearranged_twiddle_stride3_64_q31[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_256) || defined(ARM_TABLE_TWIDDLECOEF_Q31_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_q31[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_q31[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_q31[4]; +extern q31_t rearranged_twiddle_stride1_256_q31[168]; +extern q31_t rearranged_twiddle_stride2_256_q31[168]; +extern q31_t rearranged_twiddle_stride3_256_q31[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_1024) || defined(ARM_TABLE_TWIDDLECOEF_Q31_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_q31[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_q31[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_q31[5]; +extern q31_t rearranged_twiddle_stride1_1024_q31[680]; +extern q31_t rearranged_twiddle_stride2_1024_q31[680]; +extern q31_t rearranged_twiddle_stride3_1024_q31[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_4096) || defined(ARM_TABLE_TWIDDLECOEF_Q31_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_q31[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_q31[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_q31[6]; +extern q31_t rearranged_twiddle_stride1_4096_q31[2728]; +extern q31_t rearranged_twiddle_stride2_4096_q31[2728]; +extern q31_t rearranged_twiddle_stride3_4096_q31[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_16) || defined(ARM_TABLE_TWIDDLECOEF_Q15_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_q15[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_q15[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_q15[2]; +extern q15_t rearranged_twiddle_stride1_16_q15[8]; +extern q15_t rearranged_twiddle_stride2_16_q15[8]; +extern q15_t rearranged_twiddle_stride3_16_q15[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_64) || defined(ARM_TABLE_TWIDDLECOEF_Q15_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_q15[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_q15[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_q15[3]; +extern q15_t rearranged_twiddle_stride1_64_q15[40]; +extern q15_t rearranged_twiddle_stride2_64_q15[40]; +extern q15_t rearranged_twiddle_stride3_64_q15[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_256) || defined(ARM_TABLE_TWIDDLECOEF_Q15_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_q15[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_q15[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_q15[4]; +extern q15_t rearranged_twiddle_stride1_256_q15[168]; +extern q15_t rearranged_twiddle_stride2_256_q15[168]; +extern q15_t rearranged_twiddle_stride3_256_q15[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_1024) || defined(ARM_TABLE_TWIDDLECOEF_Q15_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_q15[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_q15[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_q15[5]; +extern q15_t rearranged_twiddle_stride1_1024_q15[680]; +extern q15_t rearranged_twiddle_stride2_1024_q15[680]; +extern q15_t rearranged_twiddle_stride3_1024_q15[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_4096) || defined(ARM_TABLE_TWIDDLECOEF_Q15_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_q15[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_q15[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_q15[6]; +extern q15_t rearranged_twiddle_stride1_4096_q15[2728]; +extern q15_t rearranged_twiddle_stride2_4096_q15[2728]; +extern q15_t rearranged_twiddle_stride3_4096_q15[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#endif /*_ARM_MVE_TABLES_H*/ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h new file mode 100644 index 0000000000..0ce9464bcb --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h @@ -0,0 +1,372 @@ +/****************************************************************************** + * @file arm_vec_math.h + * @brief Public header file for CMSIS DSP Library + * @version V1.7.0 + * @date 15. October 2019 + ******************************************************************************/ +/* + * Copyright (c) 2010-2019 Arm Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_VEC_MATH_H +#define _ARM_VEC_MATH_H + +#include "arm_math.h" +#include "arm_common_tables.h" +#include "arm_helium_utils.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +#if (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) + +#define INV_NEWTON_INIT_F32 0x7EF127EA + +static const float32_t __logf_rng_f32=0.693147180f; + + +/* fast inverse approximation (3x newton) */ +__STATIC_INLINE f32x4_t vrecip_medprec_f32( + f32x4_t x) +{ + q31x4_t m; + f32x4_t b; + any32x4_t xinv; + f32x4_t ax = vabsq(x); + + xinv.f = ax; + m = 0x3F800000 - (xinv.i & 0x7F800000); + xinv.i = xinv.i + m; + xinv.f = 1.41176471f - 0.47058824f * xinv.f; + xinv.i = xinv.i + m; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + xinv.f = vdupq_m(xinv.f, INFINITY, vcmpeqq(x, 0.0f)); + /* + * restore sign + */ + xinv.f = vnegq_m(xinv.f, xinv.f, vcmpltq(x, 0.0f)); + + return xinv.f; +} + +/* fast inverse approximation (4x newton) */ +__STATIC_INLINE f32x4_t vrecip_hiprec_f32( + f32x4_t x) +{ + q31x4_t m; + f32x4_t b; + any32x4_t xinv; + f32x4_t ax = vabsq(x); + + xinv.f = ax; + + m = 0x3F800000 - (xinv.i & 0x7F800000); + xinv.i = xinv.i + m; + xinv.f = 1.41176471f - 0.47058824f * xinv.f; + xinv.i = xinv.i + m; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + xinv.f = vdupq_m(xinv.f, INFINITY, vcmpeqq(x, 0.0f)); + /* + * restore sign + */ + xinv.f = vnegq_m(xinv.f, xinv.f, vcmpltq(x, 0.0f)); + + return xinv.f; +} + +__STATIC_INLINE f32x4_t vdiv_f32( + f32x4_t num, f32x4_t den) +{ + return vmulq(num, vrecip_hiprec_f32(den)); +} + +/** + @brief Single-precision taylor dev. + @param[in] x f32 quad vector input + @param[in] coeffs f32 quad vector coeffs + @return destination f32 quad vector + */ + +__STATIC_INLINE f32x4_t vtaylor_polyq_f32( + f32x4_t x, + const float32_t * coeffs) +{ + f32x4_t A = vfmasq(vdupq_n_f32(coeffs[4]), x, coeffs[0]); + f32x4_t B = vfmasq(vdupq_n_f32(coeffs[6]), x, coeffs[2]); + f32x4_t C = vfmasq(vdupq_n_f32(coeffs[5]), x, coeffs[1]); + f32x4_t D = vfmasq(vdupq_n_f32(coeffs[7]), x, coeffs[3]); + f32x4_t x2 = vmulq(x, x); + f32x4_t x4 = vmulq(x2, x2); + f32x4_t res = vfmaq(vfmaq_f32(A, B, x2), vfmaq_f32(C, D, x2), x4); + + return res; +} + +__STATIC_INLINE f32x4_t vmant_exp_f32( + f32x4_t x, + int32x4_t * e) +{ + any32x4_t r; + int32x4_t n; + + r.f = x; + n = r.i >> 23; + n = n - 127; + r.i = r.i - (n << 23); + + *e = n; + return r.f; +} + + +__STATIC_INLINE f32x4_t vlogq_f32(f32x4_t vecIn) +{ + q31x4_t vecExpUnBiased; + f32x4_t vecTmpFlt0, vecTmpFlt1; + f32x4_t vecAcc0, vecAcc1, vecAcc2, vecAcc3; + f32x4_t vecExpUnBiasedFlt; + + /* + * extract exponent + */ + vecTmpFlt1 = vmant_exp_f32(vecIn, &vecExpUnBiased); + + vecTmpFlt0 = vecTmpFlt1 * vecTmpFlt1; + /* + * a = (__logf_lut_f32[4] * r.f) + (__logf_lut_f32[0]); + */ + vecAcc0 = vdupq_n_f32(__logf_lut_f32[0]); + vecAcc0 = vfmaq(vecAcc0, vecTmpFlt1, __logf_lut_f32[4]); + /* + * b = (__logf_lut_f32[6] * r.f) + (__logf_lut_f32[2]); + */ + vecAcc1 = vdupq_n_f32(__logf_lut_f32[2]); + vecAcc1 = vfmaq(vecAcc1, vecTmpFlt1, __logf_lut_f32[6]); + /* + * c = (__logf_lut_f32[5] * r.f) + (__logf_lut_f32[1]); + */ + vecAcc2 = vdupq_n_f32(__logf_lut_f32[1]); + vecAcc2 = vfmaq(vecAcc2, vecTmpFlt1, __logf_lut_f32[5]); + /* + * d = (__logf_lut_f32[7] * r.f) + (__logf_lut_f32[3]); + */ + vecAcc3 = vdupq_n_f32(__logf_lut_f32[3]); + vecAcc3 = vfmaq(vecAcc3, vecTmpFlt1, __logf_lut_f32[7]); + /* + * a = a + b * xx; + */ + vecAcc0 = vfmaq(vecAcc0, vecAcc1, vecTmpFlt0); + /* + * c = c + d * xx; + */ + vecAcc2 = vfmaq(vecAcc2, vecAcc3, vecTmpFlt0); + /* + * xx = xx * xx; + */ + vecTmpFlt0 = vecTmpFlt0 * vecTmpFlt0; + vecExpUnBiasedFlt = vcvtq_f32_s32(vecExpUnBiased); + /* + * r.f = a + c * xx; + */ + vecAcc0 = vfmaq(vecAcc0, vecAcc2, vecTmpFlt0); + /* + * add exponent + * r.f = r.f + ((float32_t) m) * __logf_rng_f32; + */ + vecAcc0 = vfmaq(vecAcc0, vecExpUnBiasedFlt, __logf_rng_f32); + // set log0 down to -inf + vecAcc0 = vdupq_m(vecAcc0, -INFINITY, vcmpeqq(vecIn, 0.0f)); + return vecAcc0; +} + +__STATIC_INLINE f32x4_t vexpq_f32( + f32x4_t x) +{ + // Perform range reduction [-log(2),log(2)] + int32x4_t m = vcvtq_s32_f32(vmulq_n_f32(x, 1.4426950408f)); + f32x4_t val = vfmsq_f32(x, vcvtq_f32_s32(m), vdupq_n_f32(0.6931471805f)); + + // Polynomial Approximation + f32x4_t poly = vtaylor_polyq_f32(val, exp_tab); + + // Reconstruct + poly = (f32x4_t) (vqaddq_s32((q31x4_t) (poly), vqshlq_n_s32(m, 23))); + + poly = vdupq_m(poly, 0.0f, vcmpltq_n_s32(m, -126)); + return poly; +} + +__STATIC_INLINE f32x4_t arm_vec_exponent_f32(f32x4_t x, int32_t nb) +{ + f32x4_t r = x; + nb--; + while (nb > 0) { + r = vmulq(r, x); + nb--; + } + return (r); +} + +__STATIC_INLINE f32x4_t vrecip_f32(f32x4_t vecIn) +{ + f32x4_t vecSx, vecW, vecTmp; + any32x4_t v; + + vecSx = vabsq(vecIn); + + v.f = vecIn; + v.i = vsubq(vdupq_n_s32(INV_NEWTON_INIT_F32), v.i); + + vecW = vmulq(vecSx, v.f); + + // v.f = v.f * (8 + w * (-28 + w * (56 + w * (-70 + w *(56 + w * (-28 + w * (8 - w))))))); + vecTmp = vsubq(vdupq_n_f32(8.0f), vecW); + vecTmp = vfmasq(vecW, vecTmp, -28.0f); + vecTmp = vfmasq(vecW, vecTmp, 56.0f); + vecTmp = vfmasq(vecW, vecTmp, -70.0f); + vecTmp = vfmasq(vecW, vecTmp, 56.0f); + vecTmp = vfmasq(vecW, vecTmp, -28.0f); + vecTmp = vfmasq(vecW, vecTmp, 8.0f); + v.f = vmulq(v.f, vecTmp); + + v.f = vdupq_m(v.f, INFINITY, vcmpeqq(vecIn, 0.0f)); + /* + * restore sign + */ + v.f = vnegq_m(v.f, v.f, vcmpltq(vecIn, 0.0f)); + return v.f; +} + +__STATIC_INLINE f32x4_t vtanhq_f32( + f32x4_t val) +{ + f32x4_t x = + vminnmq_f32(vmaxnmq_f32(val, vdupq_n_f32(-10.f)), vdupq_n_f32(10.0f)); + f32x4_t exp2x = vexpq_f32(vmulq_n_f32(x, 2.f)); + f32x4_t num = vsubq_n_f32(exp2x, 1.f); + f32x4_t den = vaddq_n_f32(exp2x, 1.f); + f32x4_t tanh = vmulq_f32(num, vrecip_f32(den)); + return tanh; +} + +__STATIC_INLINE f32x4_t vpowq_f32( + f32x4_t val, + f32x4_t n) +{ + return vexpq_f32(vmulq_f32(n, vlogq_f32(val))); +} + +#endif /* (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE)*/ + +#if (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) +#endif /* (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) */ + +#if (defined(ARM_MATH_NEON) || defined(ARM_MATH_NEON_EXPERIMENTAL)) && !defined(ARM_MATH_AUTOVECTORIZE) + +#include "NEMath.h" +/** + * @brief Vectorized integer exponentiation + * @param[in] x value + * @param[in] nb integer exponent >= 1 + * @return x^nb + * + */ +__STATIC_INLINE float32x4_t arm_vec_exponent_f32(float32x4_t x, int32_t nb) +{ + float32x4_t r = x; + nb --; + while(nb > 0) + { + r = vmulq_f32(r , x); + nb--; + } + return(r); +} + + +__STATIC_INLINE float32x4_t __arm_vec_sqrt_f32_neon(float32x4_t x) +{ + float32x4_t x1 = vmaxq_f32(x, vdupq_n_f32(FLT_MIN)); + float32x4_t e = vrsqrteq_f32(x1); + e = vmulq_f32(vrsqrtsq_f32(vmulq_f32(x1, e), e), e); + e = vmulq_f32(vrsqrtsq_f32(vmulq_f32(x1, e), e), e); + return vmulq_f32(x, e); +} + +__STATIC_INLINE int16x8_t __arm_vec_sqrt_q15_neon(int16x8_t vec) +{ + float32x4_t tempF; + int32x4_t tempHI,tempLO; + + tempLO = vmovl_s16(vget_low_s16(vec)); + tempF = vcvtq_n_f32_s32(tempLO,15); + tempF = __arm_vec_sqrt_f32_neon(tempF); + tempLO = vcvtq_n_s32_f32(tempF,15); + + tempHI = vmovl_s16(vget_high_s16(vec)); + tempF = vcvtq_n_f32_s32(tempHI,15); + tempF = __arm_vec_sqrt_f32_neon(tempF); + tempHI = vcvtq_n_s32_f32(tempF,15); + + return(vcombine_s16(vqmovn_s32(tempLO),vqmovn_s32(tempHI))); +} + +__STATIC_INLINE int32x4_t __arm_vec_sqrt_q31_neon(int32x4_t vec) +{ + float32x4_t temp; + + temp = vcvtq_n_f32_s32(vec,31); + temp = __arm_vec_sqrt_f32_neon(temp); + return(vcvtq_n_s32_f32(temp,31)); +} + +#endif /* (defined(ARM_MATH_NEON) || defined(ARM_MATH_NEON_EXPERIMENTAL)) && !defined(ARM_MATH_AUTOVECTORIZE) */ + +#ifdef __cplusplus +} +#endif + + +#endif /* _ARM_VEC_MATH_H */ + +/** + * + * End of file. + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h new file mode 100644 index 0000000000..fe49915d96 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h @@ -0,0 +1,885 @@ +/****************************************************************************** + * @file cmsis_armcc.h + * @brief CMSIS compiler ARMCC (Arm Compiler 5) header file + * @version V5.2.1 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_ARMCC_H +#define __CMSIS_ARMCC_H + + +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677) + #error "Please use Arm Compiler Toolchain V4.0.677 or later!" +#endif + +/* CMSIS compiler control architecture macros */ +#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \ + (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) ) + #define __ARM_ARCH_6M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1)) + #define __ARM_ARCH_7M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1)) + #define __ARM_ARCH_7EM__ 1 +#endif + + /* __ARM_ARCH_8M_BASE__ not applicable */ + /* __ARM_ARCH_8M_MAIN__ not applicable */ + /* __ARM_ARCH_8_1M_MAIN__ not applicable */ + +/* CMSIS compiler control DSP macros */ +#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + #define __ARM_FEATURE_DSP 1 +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE static __forceinline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __declspec(noreturn) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed)) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT __packed struct +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION __packed union +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x))) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr))) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr))) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __memory_changed() +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); */ + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xFFU); +} + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + register uint32_t __regBasePriMax __ASM("basepri_max"); + __regBasePriMax = (basePri & 0xFFU); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1U); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} +#endif + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} +#endif + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +#define __ROR __ror + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __breakpoint(value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + #define __RBIT __rbit +#else +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ + return result; +} +#endif + + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) +#else + #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) +#else + #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) +#else + #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXB(value, ptr) __strex(value, ptr) +#else + #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXH(value, ptr) __strex(value, ptr) +#else + #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXW(value, ptr) __strex(value, ptr) +#else + #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __clrex + + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) +{ + rrx r0, r0 + bx lr +} +#endif + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRBT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRHT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRT(value, ptr) __strt(value, ptr) + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +#define __SADD8 __sadd8 +#define __QADD8 __qadd8 +#define __SHADD8 __shadd8 +#define __UADD8 __uadd8 +#define __UQADD8 __uqadd8 +#define __UHADD8 __uhadd8 +#define __SSUB8 __ssub8 +#define __QSUB8 __qsub8 +#define __SHSUB8 __shsub8 +#define __USUB8 __usub8 +#define __UQSUB8 __uqsub8 +#define __UHSUB8 __uhsub8 +#define __SADD16 __sadd16 +#define __QADD16 __qadd16 +#define __SHADD16 __shadd16 +#define __UADD16 __uadd16 +#define __UQADD16 __uqadd16 +#define __UHADD16 __uhadd16 +#define __SSUB16 __ssub16 +#define __QSUB16 __qsub16 +#define __SHSUB16 __shsub16 +#define __USUB16 __usub16 +#define __UQSUB16 __uqsub16 +#define __UHSUB16 __uhsub16 +#define __SASX __sasx +#define __QASX __qasx +#define __SHASX __shasx +#define __UASX __uasx +#define __UQASX __uqasx +#define __UHASX __uhasx +#define __SSAX __ssax +#define __QSAX __qsax +#define __SHSAX __shsax +#define __USAX __usax +#define __UQSAX __uqsax +#define __UHSAX __uhsax +#define __USAD8 __usad8 +#define __USADA8 __usada8 +#define __SSAT16 __ssat16 +#define __USAT16 __usat16 +#define __UXTB16 __uxtb16 +#define __UXTAB16 __uxtab16 +#define __SXTB16 __sxtb16 +#define __SXTAB16 __sxtab16 +#define __SMUAD __smuad +#define __SMUADX __smuadx +#define __SMLAD __smlad +#define __SMLADX __smladx +#define __SMLALD __smlald +#define __SMLALDX __smlaldx +#define __SMUSD __smusd +#define __SMUSDX __smusdx +#define __SMLSD __smlsd +#define __SMLSDX __smlsdx +#define __SMLSLD __smlsld +#define __SMLSLDX __smlsldx +#define __SEL __sel +#define __QADD __qadd +#define __QSUB __qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ + ((int64_t)(ARG3) << 32U) ) >> 32U)) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCC_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h new file mode 100644 index 0000000000..a8c22afe26 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h @@ -0,0 +1,1467 @@ +/****************************************************************************** + * @file cmsis_armclang.h + * @brief CMSIS compiler armclang (Arm Compiler 6) header file + * @version V5.3.1 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ + +#ifndef __CMSIS_ARMCLANG_H +#define __CMSIS_ARMCLANG_H + +#pragma clang system_header /* treat file as system include file */ + +#ifndef __ARM_COMPAT_H +#include /* Compatibility header for Arm Compiler 5 intrinsics */ +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); see arm_compat.h */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); see arm_compat.h */ + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr +#else +#define __get_FPSCR() ((uint32_t)0U) +#endif + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __set_FPSCR __builtin_arm_set_fpscr +#else +#define __set_FPSCR(x) ((void)(x)) +#endif + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_RW_REG(r) "+l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_RW_REG(r) "+r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __builtin_arm_nop + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __builtin_arm_wfi + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __builtin_arm_wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __builtin_arm_sev + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +#define __ISB() __builtin_arm_isb(0xF) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __builtin_arm_dsb(0xF) + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __builtin_arm_dmb(0xF) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV(value) __builtin_bswap32(value) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV16(value) __ROR(__REV(value), 16) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REVSH(value) (int16_t)__builtin_bswap16(value) + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __builtin_arm_rbit + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM Compiler 6.10 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB (uint8_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH (uint16_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW (uint32_t)__builtin_arm_ldrex + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW (uint32_t)__builtin_arm_strex + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __builtin_arm_clrex + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __builtin_arm_ssat + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __builtin_arm_usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDAEXB (uint8_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDAEXH (uint16_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDAEX (uint32_t)__builtin_arm_ldaex + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXB (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXH (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEX (uint32_t)__builtin_arm_stlex + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +#define __SADD8 __builtin_arm_sadd8 +#define __QADD8 __builtin_arm_qadd8 +#define __SHADD8 __builtin_arm_shadd8 +#define __UADD8 __builtin_arm_uadd8 +#define __UQADD8 __builtin_arm_uqadd8 +#define __UHADD8 __builtin_arm_uhadd8 +#define __SSUB8 __builtin_arm_ssub8 +#define __QSUB8 __builtin_arm_qsub8 +#define __SHSUB8 __builtin_arm_shsub8 +#define __USUB8 __builtin_arm_usub8 +#define __UQSUB8 __builtin_arm_uqsub8 +#define __UHSUB8 __builtin_arm_uhsub8 +#define __SADD16 __builtin_arm_sadd16 +#define __QADD16 __builtin_arm_qadd16 +#define __SHADD16 __builtin_arm_shadd16 +#define __UADD16 __builtin_arm_uadd16 +#define __UQADD16 __builtin_arm_uqadd16 +#define __UHADD16 __builtin_arm_uhadd16 +#define __SSUB16 __builtin_arm_ssub16 +#define __QSUB16 __builtin_arm_qsub16 +#define __SHSUB16 __builtin_arm_shsub16 +#define __USUB16 __builtin_arm_usub16 +#define __UQSUB16 __builtin_arm_uqsub16 +#define __UHSUB16 __builtin_arm_uhsub16 +#define __SASX __builtin_arm_sasx +#define __QASX __builtin_arm_qasx +#define __SHASX __builtin_arm_shasx +#define __UASX __builtin_arm_uasx +#define __UQASX __builtin_arm_uqasx +#define __UHASX __builtin_arm_uhasx +#define __SSAX __builtin_arm_ssax +#define __QSAX __builtin_arm_qsax +#define __SHSAX __builtin_arm_shsax +#define __USAX __builtin_arm_usax +#define __UQSAX __builtin_arm_uqsax +#define __UHSAX __builtin_arm_uhsax +#define __USAD8 __builtin_arm_usad8 +#define __USADA8 __builtin_arm_usada8 +#define __SSAT16 __builtin_arm_ssat16 +#define __USAT16 __builtin_arm_usat16 +#define __UXTB16 __builtin_arm_uxtb16 +#define __UXTAB16 __builtin_arm_uxtab16 +#define __SXTB16 __builtin_arm_sxtb16 +#define __SXTAB16 __builtin_arm_sxtab16 +#define __SMUAD __builtin_arm_smuad +#define __SMUADX __builtin_arm_smuadx +#define __SMLAD __builtin_arm_smlad +#define __SMLADX __builtin_arm_smladx +#define __SMLALD __builtin_arm_smlald +#define __SMLALDX __builtin_arm_smlaldx +#define __SMUSD __builtin_arm_smusd +#define __SMUSDX __builtin_arm_smusdx +#define __SMLSD __builtin_arm_smlsd +#define __SMLSDX __builtin_arm_smlsdx +#define __SMLSLD __builtin_arm_smlsld +#define __SMLSLDX __builtin_arm_smlsldx +#define __SEL __builtin_arm_sel +#define __QADD __builtin_arm_qadd +#define __QSUB __builtin_arm_qsub + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCLANG_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h new file mode 100644 index 0000000000..cdc0690747 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h @@ -0,0 +1,1893 @@ +/****************************************************************************** + * @file cmsis_armclang_ltm.h + * @brief CMSIS compiler armclang (Arm Compiler 6) header file + * @version V1.3.0 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2018-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ + +#ifndef __CMSIS_ARMCLANG_H +#define __CMSIS_ARMCLANG_H + +#pragma clang system_header /* treat file as system include file */ + +#ifndef __ARM_COMPAT_H +#include /* Compatibility header for Arm Compiler 5 intrinsics */ +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); see arm_compat.h */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); see arm_compat.h */ + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr +#else +#define __get_FPSCR() ((uint32_t)0U) +#endif + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __set_FPSCR __builtin_arm_set_fpscr +#else +#define __set_FPSCR(x) ((void)(x)) +#endif + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __builtin_arm_nop + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __builtin_arm_wfi + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __builtin_arm_wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __builtin_arm_sev + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +#define __ISB() __builtin_arm_isb(0xF) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __builtin_arm_dsb(0xF) + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __builtin_arm_dmb(0xF) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV(value) __builtin_bswap32(value) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV16(value) __ROR(__REV(value), 16) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REVSH(value) (int16_t)__builtin_bswap16(value) + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __builtin_arm_rbit + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM Compiler 6.10 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB (uint8_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH (uint16_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW (uint32_t)__builtin_arm_ldrex + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW (uint32_t)__builtin_arm_strex + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __builtin_arm_clrex + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __builtin_arm_ssat + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __builtin_arm_usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDAEXB (uint8_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDAEXH (uint16_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDAEX (uint32_t)__builtin_arm_ldaex + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXB (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEXH (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STLEX (uint32_t)__builtin_arm_stlex + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCLANG_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h new file mode 100644 index 0000000000..8d3ab9721e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h @@ -0,0 +1,283 @@ +/****************************************************************************** + * @file cmsis_compiler.h + * @brief CMSIS compiler generic header file + * @version V5.1.0 + * @date 09. October 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_COMPILER_H +#define __CMSIS_COMPILER_H + +#include + +/* + * Arm Compiler 4/5 + */ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + + +/* + * Arm Compiler 6.6 LTM (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) + #include "cmsis_armclang_ltm.h" + + /* + * Arm Compiler above 6.10.1 (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) + #include "cmsis_armclang.h" + + +/* + * GNU Compiler + */ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + + +/* + * IAR Compiler + */ +#elif defined ( __ICCARM__ ) + #include + + +/* + * TI Arm Compiler + */ +#elif defined ( __TI_ARM__ ) + #include + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __attribute__((packed)) + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed)) + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed)) + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) + #endif + #ifndef __RESTRICT + #define __RESTRICT __restrict + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +/* + * TASKING Compiler + */ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __packed__ + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __packed__ + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __packed__ + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __packed__ T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __align(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +/* + * COSMIC Compiler + */ +#elif defined ( __CSMC__ ) + #include + + #ifndef __ASM + #define __ASM _asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + // NO RETURN is automatically detected hence no warning here + #define __NO_RETURN + #endif + #ifndef __USED + #warning No compiler specific solution for __USED. __USED is ignored. + #define __USED + #endif + #ifndef __WEAK + #define __WEAK __weak + #endif + #ifndef __PACKED + #define __PACKED @packed + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT @packed struct + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION @packed union + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + @packed struct T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. + #define __ALIGNED(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +#else + #error Unknown compiler. +#endif + + +#endif /* __CMSIS_COMPILER_H */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h new file mode 100644 index 0000000000..51682042b5 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h @@ -0,0 +1,2177 @@ +/****************************************************************************** + * @file cmsis_gcc.h + * @brief CMSIS compiler GCC header file + * @version V5.3.0 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_GCC_H +#define __CMSIS_GCC_H + +/* ignore some GCC warnings */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wsign-conversion" +#pragma GCC diagnostic ignored "-Wconversion" +#pragma GCC diagnostic ignored "-Wunused-parameter" + +/* Fallback for __has_builtin */ +#ifndef __has_builtin + #define __has_builtin(x) (0) +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START + +/** + \brief Initializes data and bss sections + \details This default implementations initialized all data and additional bss + sections relying on .copy.table and .zero.table specified properly + in the used linker script. + + */ +__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) +{ + extern void _start(void) __NO_RETURN; + + typedef struct { + uint32_t const* src; + uint32_t* dest; + uint32_t wlen; + } __copy_table_t; + + typedef struct { + uint32_t* dest; + uint32_t wlen; + } __zero_table_t; + + extern const __copy_table_t __copy_table_start__; + extern const __copy_table_t __copy_table_end__; + extern const __zero_table_t __zero_table_start__; + extern const __zero_table_t __zero_table_end__; + + for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = pTable->src[i]; + } + } + + for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = 0u; + } + } + + _start(); +} + +#define __PROGRAM_START __cmsis_start +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP __StackTop +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT __StackLimit +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section(".vectors"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i" : : : "memory"); +} + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i" : : : "memory"); +} + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f" : : : "memory"); +} + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f" : : : "memory"); +} + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_get_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + return __builtin_arm_get_fpscr(); +#else + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#endif +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_set_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + __builtin_arm_set_fpscr(fpscr); +#else + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); +#endif +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_RW_REG(r) "+l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_RW_REG(r) "+r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP() __ASM volatile ("nop") + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI() __ASM volatile ("wfi":::"memory") + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE() __ASM volatile ("wfe":::"memory") + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV() __ASM volatile ("sev") + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +__STATIC_FORCEINLINE void __ISB(void) +{ + __ASM volatile ("isb 0xF":::"memory"); +} + + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__STATIC_FORCEINLINE void __DSB(void) +{ + __ASM volatile ("dsb 0xF":::"memory"); +} + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__STATIC_FORCEINLINE void __DMB(void) +{ + __ASM volatile ("dmb 0xF":::"memory"); +} + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else + uint32_t result; + + __ASM ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (int16_t)__builtin_bswap16(value); +#else + int16_t result; + + __ASM ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + __ASM ("rbit %0, %1" : "=r" (result) : "r" (value) ); +#else + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ +#endif + return result; +} + + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); + return(result); +} + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +__STATIC_FORCEINLINE void __CLREX(void) +{ + __ASM volatile ("clrex" ::: "memory"); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1, ARG2) \ +__extension__ \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1, ARG2) \ + __extension__ \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1, ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + +#define __USAT16(ARG1, ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16_RORn(uint32_t op1, uint32_t rotate) +{ + uint32_t result; + + __ASM ("sxtb16 %0, %1, ROR %2" : "=r" (result) : "r" (op1), "i" (rotate) ); + + return result; +} + +__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#if 0 +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) +#endif + +#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ + ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) + +#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ + ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#pragma GCC diagnostic pop + +#endif /* __CMSIS_GCC_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h new file mode 100644 index 0000000000..b9c90bf7ba --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h @@ -0,0 +1,968 @@ +/****************************************************************************** + * @file cmsis_iccarm.h + * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file + * @version V5.2.0 + * @date 28. January 2020 + ******************************************************************************/ + +//------------------------------------------------------------------------------ +// +// Copyright (c) 2017-2019 IAR Systems +// Copyright (c) 2017-2019 Arm Limited. All rights reserved. +// +// SPDX-License-Identifier: Apache-2.0 +// +// Licensed under the Apache License, Version 2.0 (the "License") +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +//------------------------------------------------------------------------------ + + +#ifndef __CMSIS_ICCARM_H__ +#define __CMSIS_ICCARM_H__ + +#ifndef __ICCARM__ + #error This file should only be compiled by ICCARM +#endif + +#pragma system_include + +#define __IAR_FT _Pragma("inline=forced") __intrinsic + +#if (__VER__ >= 8000000) + #define __ICCARM_V8 1 +#else + #define __ICCARM_V8 0 +#endif + +#ifndef __ALIGNED + #if __ICCARM_V8 + #define __ALIGNED(x) __attribute__((aligned(x))) + #elif (__VER__ >= 7080000) + /* Needs IAR language extensions */ + #define __ALIGNED(x) __attribute__((aligned(x))) + #else + #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. + #define __ALIGNED(x) + #endif +#endif + + +/* Define compiler macros for CPU architecture, used in CMSIS 5. + */ +#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ +/* Macros already defined */ +#else + #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' + #if __ARM_ARCH == 6 + #define __ARM_ARCH_6M__ 1 + #elif __ARM_ARCH == 7 + #if __ARM_FEATURE_DSP + #define __ARM_ARCH_7EM__ 1 + #else + #define __ARM_ARCH_7M__ 1 + #endif + #endif /* __ARM_ARCH */ + #endif /* __ARM_ARCH_PROFILE == 'M' */ +#endif + +/* Alternativ core deduction for older ICCARM's */ +#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ + !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) + #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) + #define __ARM_ARCH_6M__ 1 + #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) + #define __ARM_ARCH_7M__ 1 + #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) + #define __ARM_ARCH_7EM__ 1 + #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #else + #error "Unknown target." + #endif +#endif + + + +#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 + #define __IAR_M0_FAMILY 1 +#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 + #define __IAR_M0_FAMILY 1 +#else + #define __IAR_M0_FAMILY 0 +#endif + + +#ifndef __ASM + #define __ASM __asm +#endif + +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +#ifndef __INLINE + #define __INLINE inline +#endif + +#ifndef __NO_RETURN + #if __ICCARM_V8 + #define __NO_RETURN __attribute__((__noreturn__)) + #else + #define __NO_RETURN _Pragma("object_attribute=__noreturn") + #endif +#endif + +#ifndef __PACKED + #if __ICCARM_V8 + #define __PACKED __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED __packed + #endif +#endif + +#ifndef __PACKED_STRUCT + #if __ICCARM_V8 + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_STRUCT __packed struct + #endif +#endif + +#ifndef __PACKED_UNION + #if __ICCARM_V8 + #define __PACKED_UNION union __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_UNION __packed union + #endif +#endif + +#ifndef __RESTRICT + #if __ICCARM_V8 + #define __RESTRICT __restrict + #else + /* Needs IAR language extensions */ + #define __RESTRICT restrict + #endif +#endif + +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif + +#ifndef __FORCEINLINE + #define __FORCEINLINE _Pragma("inline=forced") +#endif + +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE +#endif + +#ifndef __UNALIGNED_UINT16_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint16_t __iar_uint16_read(void const *ptr) +{ + return *(__packed uint16_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) +#endif + + +#ifndef __UNALIGNED_UINT16_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) +{ + *(__packed uint16_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint32_t __iar_uint32_read(void const *ptr) +{ + return *(__packed uint32_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) +#endif + +#ifndef __UNALIGNED_UINT32_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) +{ + *(__packed uint32_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32 /* deprecated */ +#pragma language=save +#pragma language=extended +__packed struct __iar_u32 { uint32_t v; }; +#pragma language=restore +#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) +#endif + +#ifndef __USED + #if __ICCARM_V8 + #define __USED __attribute__((used)) + #else + #define __USED _Pragma("__root") + #endif +#endif + +#ifndef __WEAK + #if __ICCARM_V8 + #define __WEAK __attribute__((weak)) + #else + #define __WEAK _Pragma("__weak") + #endif +#endif + +#ifndef __PROGRAM_START +#define __PROGRAM_START __iar_program_start +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP CSTACK$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT CSTACK$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __vector_table +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE @".intvec" +#endif + +#ifndef __ICCARM_INTRINSICS_VERSION__ + #define __ICCARM_INTRINSICS_VERSION__ 0 +#endif + +#if __ICCARM_INTRINSICS_VERSION__ == 2 + + #if defined(__CLZ) + #undef __CLZ + #endif + #if defined(__REVSH) + #undef __REVSH + #endif + #if defined(__RBIT) + #undef __RBIT + #endif + #if defined(__SSAT) + #undef __SSAT + #endif + #if defined(__USAT) + #undef __USAT + #endif + + #include "iccarm_builtin.h" + + #define __disable_fault_irq __iar_builtin_disable_fiq + #define __disable_irq __iar_builtin_disable_interrupt + #define __enable_fault_irq __iar_builtin_enable_fiq + #define __enable_irq __iar_builtin_enable_interrupt + #define __arm_rsr __iar_builtin_rsr + #define __arm_wsr __iar_builtin_wsr + + + #define __get_APSR() (__arm_rsr("APSR")) + #define __get_BASEPRI() (__arm_rsr("BASEPRI")) + #define __get_CONTROL() (__arm_rsr("CONTROL")) + #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) + + #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + #define __get_FPSCR() (__arm_rsr("FPSCR")) + #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) + #else + #define __get_FPSCR() ( 0 ) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #define __get_IPSR() (__arm_rsr("IPSR")) + #define __get_MSP() (__arm_rsr("MSP")) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __get_MSPLIM() (0U) + #else + #define __get_MSPLIM() (__arm_rsr("MSPLIM")) + #endif + #define __get_PRIMASK() (__arm_rsr("PRIMASK")) + #define __get_PSP() (__arm_rsr("PSP")) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __get_PSPLIM() (0U) + #else + #define __get_PSPLIM() (__arm_rsr("PSPLIM")) + #endif + + #define __get_xPSR() (__arm_rsr("xPSR")) + + #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) + #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) + #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) + #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) + #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __set_MSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) + #endif + #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) + #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __set_PSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) + #endif + + #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) + #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) + #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) + #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) + #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) + #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) + #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) + #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) + #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) + #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) + #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) + #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) + #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) + #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __TZ_get_PSPLIM_NS() (0U) + #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) + #else + #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) + #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) + #endif + + #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) + #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) + + #define __NOP __iar_builtin_no_operation + + #define __CLZ __iar_builtin_CLZ + #define __CLREX __iar_builtin_CLREX + + #define __DMB __iar_builtin_DMB + #define __DSB __iar_builtin_DSB + #define __ISB __iar_builtin_ISB + + #define __LDREXB __iar_builtin_LDREXB + #define __LDREXH __iar_builtin_LDREXH + #define __LDREXW __iar_builtin_LDREX + + #define __RBIT __iar_builtin_RBIT + #define __REV __iar_builtin_REV + #define __REV16 __iar_builtin_REV16 + + __IAR_FT int16_t __REVSH(int16_t val) + { + return (int16_t) __iar_builtin_REVSH(val); + } + + #define __ROR __iar_builtin_ROR + #define __RRX __iar_builtin_RRX + + #define __SEV __iar_builtin_SEV + + #if !__IAR_M0_FAMILY + #define __SSAT __iar_builtin_SSAT + #endif + + #define __STREXB __iar_builtin_STREXB + #define __STREXH __iar_builtin_STREXH + #define __STREXW __iar_builtin_STREX + + #if !__IAR_M0_FAMILY + #define __USAT __iar_builtin_USAT + #endif + + #define __WFE __iar_builtin_WFE + #define __WFI __iar_builtin_WFI + + #if __ARM_MEDIA__ + #define __SADD8 __iar_builtin_SADD8 + #define __QADD8 __iar_builtin_QADD8 + #define __SHADD8 __iar_builtin_SHADD8 + #define __UADD8 __iar_builtin_UADD8 + #define __UQADD8 __iar_builtin_UQADD8 + #define __UHADD8 __iar_builtin_UHADD8 + #define __SSUB8 __iar_builtin_SSUB8 + #define __QSUB8 __iar_builtin_QSUB8 + #define __SHSUB8 __iar_builtin_SHSUB8 + #define __USUB8 __iar_builtin_USUB8 + #define __UQSUB8 __iar_builtin_UQSUB8 + #define __UHSUB8 __iar_builtin_UHSUB8 + #define __SADD16 __iar_builtin_SADD16 + #define __QADD16 __iar_builtin_QADD16 + #define __SHADD16 __iar_builtin_SHADD16 + #define __UADD16 __iar_builtin_UADD16 + #define __UQADD16 __iar_builtin_UQADD16 + #define __UHADD16 __iar_builtin_UHADD16 + #define __SSUB16 __iar_builtin_SSUB16 + #define __QSUB16 __iar_builtin_QSUB16 + #define __SHSUB16 __iar_builtin_SHSUB16 + #define __USUB16 __iar_builtin_USUB16 + #define __UQSUB16 __iar_builtin_UQSUB16 + #define __UHSUB16 __iar_builtin_UHSUB16 + #define __SASX __iar_builtin_SASX + #define __QASX __iar_builtin_QASX + #define __SHASX __iar_builtin_SHASX + #define __UASX __iar_builtin_UASX + #define __UQASX __iar_builtin_UQASX + #define __UHASX __iar_builtin_UHASX + #define __SSAX __iar_builtin_SSAX + #define __QSAX __iar_builtin_QSAX + #define __SHSAX __iar_builtin_SHSAX + #define __USAX __iar_builtin_USAX + #define __UQSAX __iar_builtin_UQSAX + #define __UHSAX __iar_builtin_UHSAX + #define __USAD8 __iar_builtin_USAD8 + #define __USADA8 __iar_builtin_USADA8 + #define __SSAT16 __iar_builtin_SSAT16 + #define __USAT16 __iar_builtin_USAT16 + #define __UXTB16 __iar_builtin_UXTB16 + #define __UXTAB16 __iar_builtin_UXTAB16 + #define __SXTB16 __iar_builtin_SXTB16 + #define __SXTAB16 __iar_builtin_SXTAB16 + #define __SMUAD __iar_builtin_SMUAD + #define __SMUADX __iar_builtin_SMUADX + #define __SMMLA __iar_builtin_SMMLA + #define __SMLAD __iar_builtin_SMLAD + #define __SMLADX __iar_builtin_SMLADX + #define __SMLALD __iar_builtin_SMLALD + #define __SMLALDX __iar_builtin_SMLALDX + #define __SMUSD __iar_builtin_SMUSD + #define __SMUSDX __iar_builtin_SMUSDX + #define __SMLSD __iar_builtin_SMLSD + #define __SMLSDX __iar_builtin_SMLSDX + #define __SMLSLD __iar_builtin_SMLSLD + #define __SMLSLDX __iar_builtin_SMLSLDX + #define __SEL __iar_builtin_SEL + #define __QADD __iar_builtin_QADD + #define __QSUB __iar_builtin_QSUB + #define __PKHBT __iar_builtin_PKHBT + #define __PKHTB __iar_builtin_PKHTB + #endif + +#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #define __CLZ __cmsis_iar_clz_not_active + #define __SSAT __cmsis_iar_ssat_not_active + #define __USAT __cmsis_iar_usat_not_active + #define __RBIT __cmsis_iar_rbit_not_active + #define __get_APSR __cmsis_iar_get_APSR_not_active + #endif + + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #define __get_FPSCR __cmsis_iar_get_FPSR_not_active + #define __set_FPSCR __cmsis_iar_set_FPSR_not_active + #endif + + #ifdef __INTRINSICS_INCLUDED + #error intrinsics.h is already included previously! + #endif + + #include + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #undef __CLZ + #undef __SSAT + #undef __USAT + #undef __RBIT + #undef __get_APSR + + __STATIC_INLINE uint8_t __CLZ(uint32_t data) + { + if (data == 0U) { return 32U; } + + uint32_t count = 0U; + uint32_t mask = 0x80000000U; + + while ((data & mask) == 0U) + { + count += 1U; + mask = mask >> 1U; + } + return count; + } + + __STATIC_INLINE uint32_t __RBIT(uint32_t v) + { + uint8_t sc = 31U; + uint32_t r = v; + for (v >>= 1U; v; v >>= 1U) + { + r <<= 1U; + r |= v & 1U; + sc--; + } + return (r << sc); + } + + __STATIC_INLINE uint32_t __get_APSR(void) + { + uint32_t res; + __asm("MRS %0,APSR" : "=r" (res)); + return res; + } + + #endif + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #undef __get_FPSCR + #undef __set_FPSCR + #define __get_FPSCR() (0) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #pragma diag_suppress=Pe940 + #pragma diag_suppress=Pe177 + + #define __enable_irq __enable_interrupt + #define __disable_irq __disable_interrupt + #define __NOP __no_operation + + #define __get_xPSR __get_PSR + + #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) + + __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) + { + return __LDREX((unsigned long *)ptr); + } + + __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) + { + return __STREX(value, (unsigned long *)ptr); + } + #endif + + + /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + #if (__CORTEX_M >= 0x03) + + __IAR_FT uint32_t __RRX(uint32_t value) + { + uint32_t result; + __ASM volatile("RRX %0, %1" : "=r"(result) : "r" (value)); + return(result); + } + + __IAR_FT void __set_BASEPRI_MAX(uint32_t value) + { + __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); + } + + + #define __enable_fault_irq __enable_fiq + #define __disable_fault_irq __disable_fiq + + + #endif /* (__CORTEX_M >= 0x03) */ + + __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) + { + return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); + } + + #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + __IAR_FT uint32_t __get_MSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,MSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_MSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR MSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __get_PSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_PSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) + { + __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PSP_NS(uint32_t value) + { + __asm volatile("MSR PSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_MSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSP_NS(uint32_t value) + { + __asm volatile("MSR MSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_SP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,SP_NS" : "=r" (res)); + return res; + } + __IAR_FT void __TZ_set_SP_NS(uint32_t value) + { + __asm volatile("MSR SP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) + { + __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) + { + __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) + { + __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) + { + __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); + } + + #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + +#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) + +#if __IAR_M0_FAMILY + __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) + { + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; + } + + __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) + { + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; + } +#endif + +#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + + __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) + { + uint32_t res; + __ASM volatile ("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) + { + uint32_t res; + __ASM volatile ("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) + { + uint32_t res; + __ASM volatile ("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return res; + } + + __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) + { + __ASM volatile ("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) + { + __ASM volatile ("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) + { + __ASM volatile ("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); + } + +#endif /* (__CORTEX_M >= 0x03) */ + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + + __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) + { + __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) + { + __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) + { + __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + +#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#undef __IAR_FT +#undef __IAR_M0_FAMILY +#undef __ICCARM_V8 + +#pragma diag_default=Pe940 +#pragma diag_default=Pe177 + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +#endif /* __CMSIS_ICCARM_H__ */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h new file mode 100644 index 0000000000..c999178e04 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h @@ -0,0 +1,39 @@ +/****************************************************************************** + * @file cmsis_version.h + * @brief CMSIS Core(M) Version definitions + * @version V5.0.4 + * @date 23. July 2019 + ******************************************************************************/ +/* + * Copyright (c) 2009-2019 ARM Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CMSIS_VERSION_H +#define __CMSIS_VERSION_H + +/* CMSIS Version definitions */ +#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ +#define __CM_CMSIS_VERSION_SUB ( 4U) /*!< [15:0] CMSIS Core(M) sub version */ +#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ + __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h new file mode 100644 index 0000000000..0b9f9d7818 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h @@ -0,0 +1,2129 @@ +/************************************************************************** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V5.1.1 + * @date 27. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M4 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ + __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (4U) /*!< Cortex-M Core */ + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_FP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM4_REV + #define __CM4_REV 0x0000U + #warning "__CM4_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __VTOR_PRESENT + #define __VTOR_PRESENT 1U + #warning "__VTOR_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M4 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RESERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[32U]; + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/* Media and FP Feature Register 2 Definitions */ + +#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ +#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ + +/*@} end of group CMSIS_FPU */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ +#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ +#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ + + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + __COMPILER_BARRIER(); + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __COMPILER_BARRIER(); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; + /* ARM Application Note 321 states that the M4 does not require the architectural barrier */ +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = FPU->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h new file mode 100644 index 0000000000..791a8dae65 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h @@ -0,0 +1,275 @@ +/****************************************************************************** + * @file mpu_armv7.h + * @brief CMSIS MPU API for Armv7-M MPU + * @version V5.1.1 + * @date 10. February 2020 + ******************************************************************************/ +/* + * Copyright (c) 2017-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV7_H +#define ARM_MPU_ARMV7_H + +#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes +#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes +#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes +#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes +#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes +#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte +#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes +#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes +#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes +#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes +#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes +#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes +#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes +#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes +#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes +#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte +#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes +#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes +#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes +#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes +#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes +#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes +#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes +#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes +#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes +#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte +#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes +#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes + +#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access +#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only +#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only +#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access +#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only +#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access + +/** MPU Region Base Address Register Value +* +* \param Region The region to be configured, number 0 to 15. +* \param BaseAddress The base address for the region. +*/ +#define ARM_MPU_RBAR(Region, BaseAddress) \ + (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ + ((Region) & MPU_RBAR_REGION_Msk) | \ + (MPU_RBAR_VALID_Msk)) + +/** +* MPU Memory Access Attributes +* +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +*/ +#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ + ((((TypeExtField) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ + (((IsShareable) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ + (((IsCacheable) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ + (((IsBufferable) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ + ((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ + (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ + (((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) | \ + (((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \ + (((Size) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \ + (((MPU_RASR_ENABLE_Msk)))) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ + ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) + +/** +* MPU Memory Access Attribute for strongly ordered memory. +* - TEX: 000b +* - Shareable +* - Non-cacheable +* - Non-bufferable +*/ +#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) + +/** +* MPU Memory Access Attribute for device memory. +* - TEX: 000b (if shareable) or 010b (if non-shareable) +* - Shareable or non-shareable +* - Non-cacheable +* - Bufferable (if shareable) or non-bufferable (if non-shareable) +* +* \param IsShareable Configures the device memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) + +/** +* MPU Memory Access Attribute for normal memory. +* - TEX: 1BBb (reflecting outer cacheability rules) +* - Shareable or non-shareable +* - Cacheable or non-cacheable (reflecting inner cacheability rules) +* - Bufferable or non-bufferable (reflecting inner cacheability rules) +* +* \param OuterCp Configures the outer cache policy. +* \param InnerCp Configures the inner cache policy. +* \param IsShareable Configures the memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) >> 1U), ((InnerCp) & 1U)) + +/** +* MPU Memory Access Attribute non-cacheable policy. +*/ +#define ARM_MPU_CACHEP_NOCACHE 0U + +/** +* MPU Memory Access Attribute write-back, write and read allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_WRA 1U + +/** +* MPU Memory Access Attribute write-through, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WT_NWA 2U + +/** +* MPU Memory Access Attribute write-back, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_NWA 3U + + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; //!< The region base address register value (RBAR) + uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DMB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + MPU->RNR = rnr; + MPU->RASR = 0U; +} + +/** Configure an MPU region. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) +{ + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) +{ + MPU->RNR = rnr; + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + while (cnt > MPU_TYPE_RALIASES) { + ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); + table += MPU_TYPE_RALIASES; + cnt -= MPU_TYPE_RALIASES; + } + ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); +} + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h new file mode 100644 index 0000000000..ef44ad01df --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h @@ -0,0 +1,352 @@ +/****************************************************************************** + * @file mpu_armv8.h + * @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU + * @version V5.1.2 + * @date 10. February 2020 + ******************************************************************************/ +/* + * Copyright (c) 2017-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV8_H +#define ARM_MPU_ARMV8_H + +/** \brief Attribute for device memory (outer only) */ +#define ARM_MPU_ATTR_DEVICE ( 0U ) + +/** \brief Attribute for non-cacheable, normal memory */ +#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) + +/** \brief Attribute for normal memory (outer and inner) +* \param NT Non-Transient: Set to 1 for non-transient data. +* \param WB Write-Back: Set to 1 to use write-back update policy. +* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. +* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. +*/ +#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ + ((((NT) & 1U) << 3U) | (((WB) & 1U) << 2U) | (((RA) & 1U) << 1U) | ((WA) & 1U)) + +/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) + +/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) + +/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGRE (2U) + +/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_GRE (3U) + +/** \brief Memory Attribute +* \param O Outer memory attributes +* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes +*/ +#define ARM_MPU_ATTR(O, I) ((((O) & 0xFU) << 4U) | ((((O) & 0xFU) != 0U) ? ((I) & 0xFU) : (((I) & 0x3U) << 2U))) + +/** \brief Normal memory non-shareable */ +#define ARM_MPU_SH_NON (0U) + +/** \brief Normal memory outer shareable */ +#define ARM_MPU_SH_OUTER (2U) + +/** \brief Normal memory inner shareable */ +#define ARM_MPU_SH_INNER (3U) + +/** \brief Memory access permissions +* \param RO Read-Only: Set to 1 for read-only memory. +* \param NP Non-Privileged: Set to 1 for non-privileged memory. +*/ +#define ARM_MPU_AP_(RO, NP) ((((RO) & 1U) << 1U) | ((NP) & 1U)) + +/** \brief Region Base Address Register value +* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. +* \param SH Defines the Shareability domain for this memory region. +* \param RO Read-Only: Set to 1 for a read-only memory region. +* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. +* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. +*/ +#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ + (((BASE) & MPU_RBAR_BASE_Msk) | \ + (((SH) << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ + ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ + (((XN) << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) + +/** \brief Region Limit Address Register value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR(LIMIT, IDX) \ + (((LIMIT) & MPU_RLAR_LIMIT_Msk) | \ + (((IDX) << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +#if defined(MPU_RLAR_PXN_Pos) + +/** \brief Region Limit Address Register with PXN value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \ + (((LIMIT) & MPU_RLAR_LIMIT_Msk) | \ + (((PXN) << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \ + (((IDX) << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +#endif + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; /*!< Region Base Address Register value */ + uint32_t RLAR; /*!< Region Limit Address Register value */ +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DMB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} + +#ifdef MPU_NS +/** Enable the Non-secure MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) +{ + __DMB(); + MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the Non-secure MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable_NS(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} +#endif + +/** Set the memory attribute encoding to the given MPU. +* \param mpu Pointer to the MPU to be configured. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) +{ + const uint8_t reg = idx / 4U; + const uint32_t pos = ((idx % 4U) * 8U); + const uint32_t mask = 0xFFU << pos; + + if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { + return; // invalid index + } + + mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); +} + +/** Set the memory attribute encoding. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU, idx, attr); +} + +#ifdef MPU_NS +/** Set the memory attribute encoding to the Non-secure MPU. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); +} +#endif + +/** Clear and disable the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) +{ + mpu->RNR = rnr; + mpu->RLAR = 0U; +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU, rnr); +} + +#ifdef MPU_NS +/** Clear and disable the given Non-secure MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU_NS, rnr); +} +#endif + +/** Configure the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + mpu->RNR = rnr; + mpu->RBAR = rbar; + mpu->RLAR = rlar; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); +} + +#ifdef MPU_NS +/** Configure the given Non-secure MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); +} +#endif + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table to the given MPU. +* \param mpu Pointer to the MPU registers to be used. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + if (cnt == 1U) { + mpu->RNR = rnr; + ARM_MPU_OrderedMemcpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); + } else { + uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); + uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; + + mpu->RNR = rnrBase; + while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { + uint32_t c = MPU_TYPE_RALIASES - rnrOffset; + ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); + table += c; + cnt -= c; + rnrOffset = 0U; + rnrBase += MPU_TYPE_RALIASES; + mpu->RNR = rnrBase; + } + + ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); + } +} + +/** Load the given number of MPU regions from a table. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU, rnr, table, cnt); +} + +#ifdef MPU_NS +/** Load the given number of MPU regions from a table to the Non-secure MPU. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h new file mode 100644 index 0000000000..dbd39d20c7 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h @@ -0,0 +1,337 @@ +/****************************************************************************** + * @file pmu_armv8.h + * @brief CMSIS PMU API for Armv8.1-M PMU + * @version V1.0.0 + * @date 24. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed under the Apache License, Version 2.0 (the License); you may + * not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_PMU_ARMV8_H +#define ARM_PMU_ARMV8_H + +/** + * \brief PMU Events + * \note See the Armv8.1-M Architecture Reference Manual for full details on these PMU events. + * */ + +#define ARM_PMU_SW_INCR 0x0000 /*!< Software update to the PMU_SWINC register, architecturally executed and condition code check pass */ +#define ARM_PMU_L1I_CACHE_REFILL 0x0001 /*!< L1 I-Cache refill */ +#define ARM_PMU_L1D_CACHE_REFILL 0x0003 /*!< L1 D-Cache refill */ +#define ARM_PMU_L1D_CACHE 0x0004 /*!< L1 D-Cache access */ +#define ARM_PMU_LD_RETIRED 0x0006 /*!< Memory-reading instruction architecturally executed and condition code check pass */ +#define ARM_PMU_ST_RETIRED 0x0007 /*!< Memory-writing instruction architecturally executed and condition code check pass */ +#define ARM_PMU_INST_RETIRED 0x0008 /*!< Instruction architecturally executed */ +#define ARM_PMU_EXC_TAKEN 0x0009 /*!< Exception entry */ +#define ARM_PMU_EXC_RETURN 0x000A /*!< Exception return instruction architecturally executed and the condition code check pass */ +#define ARM_PMU_PC_WRITE_RETIRED 0x000C /*!< Software change to the Program Counter (PC). Instruction is architecturally executed and condition code check pass */ +#define ARM_PMU_BR_IMMED_RETIRED 0x000D /*!< Immediate branch architecturally executed */ +#define ARM_PMU_BR_RETURN_RETIRED 0x000E /*!< Function return instruction architecturally executed and the condition code check pass */ +#define ARM_PMU_UNALIGNED_LDST_RETIRED 0x000F /*!< Unaligned memory memory-reading or memory-writing instruction architecturally executed and condition code check pass */ +#define ARM_PMU_BR_MIS_PRED 0x0010 /*!< Mispredicted or not predicted branch speculatively executed */ +#define ARM_PMU_CPU_CYCLES 0x0011 /*!< Cycle */ +#define ARM_PMU_BR_PRED 0x0012 /*!< Predictable branch speculatively executed */ +#define ARM_PMU_MEM_ACCESS 0x0013 /*!< Data memory access */ +#define ARM_PMU_L1I_CACHE 0x0014 /*!< Level 1 instruction cache access */ +#define ARM_PMU_L1D_CACHE_WB 0x0015 /*!< Level 1 data cache write-back */ +#define ARM_PMU_L2D_CACHE 0x0016 /*!< Level 2 data cache access */ +#define ARM_PMU_L2D_CACHE_REFILL 0x0017 /*!< Level 2 data cache refill */ +#define ARM_PMU_L2D_CACHE_WB 0x0018 /*!< Level 2 data cache write-back */ +#define ARM_PMU_BUS_ACCESS 0x0019 /*!< Bus access */ +#define ARM_PMU_MEMORY_ERROR 0x001A /*!< Local memory error */ +#define ARM_PMU_INST_SPEC 0x001B /*!< Instruction speculatively executed */ +#define ARM_PMU_BUS_CYCLES 0x001D /*!< Bus cycles */ +#define ARM_PMU_CHAIN 0x001E /*!< For an odd numbered counter, increment when an overflow occurs on the preceding even-numbered counter on the same PE */ +#define ARM_PMU_L1D_CACHE_ALLOCATE 0x001F /*!< Level 1 data cache allocation without refill */ +#define ARM_PMU_L2D_CACHE_ALLOCATE 0x0020 /*!< Level 2 data cache allocation without refill */ +#define ARM_PMU_BR_RETIRED 0x0021 /*!< Branch instruction architecturally executed */ +#define ARM_PMU_BR_MIS_PRED_RETIRED 0x0022 /*!< Mispredicted branch instruction architecturally executed */ +#define ARM_PMU_STALL_FRONTEND 0x0023 /*!< No operation issued because of the frontend */ +#define ARM_PMU_STALL_BACKEND 0x0024 /*!< No operation issued because of the backend */ +#define ARM_PMU_L2I_CACHE 0x0027 /*!< Level 2 instruction cache access */ +#define ARM_PMU_L2I_CACHE_REFILL 0x0028 /*!< Level 2 instruction cache refill */ +#define ARM_PMU_L3D_CACHE_ALLOCATE 0x0029 /*!< Level 3 data cache allocation without refill */ +#define ARM_PMU_L3D_CACHE_REFILL 0x002A /*!< Level 3 data cache refill */ +#define ARM_PMU_L3D_CACHE 0x002B /*!< Level 3 data cache access */ +#define ARM_PMU_L3D_CACHE_WB 0x002C /*!< Level 3 data cache write-back */ +#define ARM_PMU_LL_CACHE_RD 0x0036 /*!< Last level data cache read */ +#define ARM_PMU_LL_CACHE_MISS_RD 0x0037 /*!< Last level data cache read miss */ +#define ARM_PMU_L1D_CACHE_MISS_RD 0x0039 /*!< Level 1 data cache read miss */ +#define ARM_PMU_OP_COMPLETE 0x003A /*!< Operation retired */ +#define ARM_PMU_OP_SPEC 0x003B /*!< Operation speculatively executed */ +#define ARM_PMU_STALL 0x003C /*!< Stall cycle for instruction or operation not sent for execution */ +#define ARM_PMU_STALL_OP_BACKEND 0x003D /*!< Stall cycle for instruction or operation not sent for execution due to pipeline backend */ +#define ARM_PMU_STALL_OP_FRONTEND 0x003E /*!< Stall cycle for instruction or operation not sent for execution due to pipeline frontend */ +#define ARM_PMU_STALL_OP 0x003F /*!< Instruction or operation slots not occupied each cycle */ +#define ARM_PMU_L1D_CACHE_RD 0x0040 /*!< Level 1 data cache read */ +#define ARM_PMU_LE_RETIRED 0x0100 /*!< Loop end instruction executed */ +#define ARM_PMU_LE_SPEC 0x0101 /*!< Loop end instruction speculatively executed */ +#define ARM_PMU_BF_RETIRED 0x0104 /*!< Branch future instruction architecturally executed and condition code check pass */ +#define ARM_PMU_BF_SPEC 0x0105 /*!< Branch future instruction speculatively executed and condition code check pass */ +#define ARM_PMU_LE_CANCEL 0x0108 /*!< Loop end instruction not taken */ +#define ARM_PMU_BF_CANCEL 0x0109 /*!< Branch future instruction not taken */ +#define ARM_PMU_SE_CALL_S 0x0114 /*!< Call to secure function, resulting in Security state change */ +#define ARM_PMU_SE_CALL_NS 0x0115 /*!< Call to non-secure function, resulting in Security state change */ +#define ARM_PMU_DWT_CMPMATCH0 0x0118 /*!< DWT comparator 0 match */ +#define ARM_PMU_DWT_CMPMATCH1 0x0119 /*!< DWT comparator 1 match */ +#define ARM_PMU_DWT_CMPMATCH2 0x011A /*!< DWT comparator 2 match */ +#define ARM_PMU_DWT_CMPMATCH3 0x011B /*!< DWT comparator 3 match */ +#define ARM_PMU_MVE_INST_RETIRED 0x0200 /*!< MVE instruction architecturally executed */ +#define ARM_PMU_MVE_INST_SPEC 0x0201 /*!< MVE instruction speculatively executed */ +#define ARM_PMU_MVE_FP_RETIRED 0x0204 /*!< MVE floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_SPEC 0x0205 /*!< MVE floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_HP_RETIRED 0x0208 /*!< MVE half-precision floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_HP_SPEC 0x0209 /*!< MVE half-precision floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_SP_RETIRED 0x020C /*!< MVE single-precision floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_SP_SPEC 0x020D /*!< MVE single-precision floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_MAC_RETIRED 0x0214 /*!< MVE floating-point multiply or multiply-accumulate instruction architecturally executed */ +#define ARM_PMU_MVE_FP_MAC_SPEC 0x0215 /*!< MVE floating-point multiply or multiply-accumulate instruction speculatively executed */ +#define ARM_PMU_MVE_INT_RETIRED 0x0224 /*!< MVE integer instruction architecturally executed */ +#define ARM_PMU_MVE_INT_SPEC 0x0225 /*!< MVE integer instruction speculatively executed */ +#define ARM_PMU_MVE_INT_MAC_RETIRED 0x0228 /*!< MVE multiply or multiply-accumulate instruction architecturally executed */ +#define ARM_PMU_MVE_INT_MAC_SPEC 0x0229 /*!< MVE multiply or multiply-accumulate instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_RETIRED 0x0238 /*!< MVE load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_SPEC 0x0239 /*!< MVE load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_RETIRED 0x023C /*!< MVE load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_SPEC 0x023D /*!< MVE load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_RETIRED 0x0240 /*!< MVE store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_SPEC 0x0241 /*!< MVE store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_CONTIG_RETIRED 0x0244 /*!< MVE contiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_CONTIG_SPEC 0x0245 /*!< MVE contiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_CONTIG_RETIRED 0x0248 /*!< MVE contiguous load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_CONTIG_SPEC 0x0249 /*!< MVE contiguous load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_CONTIG_RETIRED 0x024C /*!< MVE contiguous store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_CONTIG_SPEC 0x024D /*!< MVE contiguous store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_NONCONTIG_RETIRED 0x0250 /*!< MVE non-contiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_NONCONTIG_SPEC 0x0251 /*!< MVE non-contiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_NONCONTIG_RETIRED 0x0254 /*!< MVE non-contiguous load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_NONCONTIG_SPEC 0x0255 /*!< MVE non-contiguous load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_NONCONTIG_RETIRED 0x0258 /*!< MVE non-contiguous store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_NONCONTIG_SPEC 0x0259 /*!< MVE non-contiguous store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_MULTI_RETIRED 0x025C /*!< MVE memory instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_LDST_MULTI_SPEC 0x025D /*!< MVE memory instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_LD_MULTI_RETIRED 0x0260 /*!< MVE memory load instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_LD_MULTI_SPEC 0x0261 /*!< MVE memory load instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_ST_MULTI_RETIRED 0x0261 /*!< MVE memory store instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_ST_MULTI_SPEC 0x0265 /*!< MVE memory store instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_RETIRED 0x028C /*!< MVE unaligned memory load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_SPEC 0x028D /*!< MVE unaligned memory load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_UNALIGNED_RETIRED 0x0290 /*!< MVE unaligned load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_UNALIGNED_SPEC 0x0291 /*!< MVE unaligned load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_UNALIGNED_RETIRED 0x0294 /*!< MVE unaligned store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_UNALIGNED_SPEC 0x0295 /*!< MVE unaligned store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_NONCONTIG_RETIRED 0x0298 /*!< MVE unaligned noncontiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_NONCONTIG_SPEC 0x0299 /*!< MVE unaligned noncontiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_RETIRED 0x02A0 /*!< MVE vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_SPEC 0x02A1 /*!< MVE vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_FP_RETIRED 0x02A4 /*!< MVE floating-point vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_FP_SPEC 0x02A5 /*!< MVE floating-point vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_INT_RETIRED 0x02A8 /*!< MVE integer vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_INT_SPEC 0x02A9 /*!< MVE integer vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_PRED 0x02B8 /*!< Cycles where one or more predicated beats architecturally executed */ +#define ARM_PMU_MVE_STALL 0x02CC /*!< Stall cycles caused by an MVE instruction */ +#define ARM_PMU_MVE_STALL_RESOURCE 0x02CD /*!< Stall cycles caused by an MVE instruction because of resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_MEM 0x02CE /*!< Stall cycles caused by an MVE instruction because of memory resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_FP 0x02CF /*!< Stall cycles caused by an MVE instruction because of floating-point resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_INT 0x02D0 /*!< Stall cycles caused by an MVE instruction because of integer resource conflicts */ +#define ARM_PMU_MVE_STALL_BREAK 0x02D3 /*!< Stall cycles caused by an MVE chain break */ +#define ARM_PMU_MVE_STALL_DEPENDENCY 0x02D4 /*!< Stall cycles caused by MVE register dependency */ +#define ARM_PMU_ITCM_ACCESS 0x4007 /*!< Instruction TCM access */ +#define ARM_PMU_DTCM_ACCESS 0x4008 /*!< Data TCM access */ +#define ARM_PMU_TRCEXTOUT0 0x4010 /*!< ETM external output 0 */ +#define ARM_PMU_TRCEXTOUT1 0x4011 /*!< ETM external output 1 */ +#define ARM_PMU_TRCEXTOUT2 0x4012 /*!< ETM external output 2 */ +#define ARM_PMU_TRCEXTOUT3 0x4013 /*!< ETM external output 3 */ +#define ARM_PMU_CTI_TRIGOUT4 0x4018 /*!< Cross-trigger Interface output trigger 4 */ +#define ARM_PMU_CTI_TRIGOUT5 0x4019 /*!< Cross-trigger Interface output trigger 5 */ +#define ARM_PMU_CTI_TRIGOUT6 0x401A /*!< Cross-trigger Interface output trigger 6 */ +#define ARM_PMU_CTI_TRIGOUT7 0x401B /*!< Cross-trigger Interface output trigger 7 */ + +/** \brief PMU Functions */ + +__STATIC_INLINE void ARM_PMU_Enable(void); +__STATIC_INLINE void ARM_PMU_Disable(void); + +__STATIC_INLINE void ARM_PMU_Set_EVTYPER(uint32_t num, uint32_t type); + +__STATIC_INLINE void ARM_PMU_CYCCNT_Reset(void); +__STATIC_INLINE void ARM_PMU_EVCNTR_ALL_Reset(void); + +__STATIC_INLINE void ARM_PMU_CNTR_Enable(uint32_t mask); +__STATIC_INLINE void ARM_PMU_CNTR_Disable(uint32_t mask); + +__STATIC_INLINE uint32_t ARM_PMU_Get_CCNTR(void); +__STATIC_INLINE uint32_t ARM_PMU_Get_EVCNTR(uint32_t num); + +__STATIC_INLINE uint32_t ARM_PMU_Get_CNTR_OVS(void); +__STATIC_INLINE void ARM_PMU_Set_CNTR_OVS(uint32_t mask); + +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Enable(uint32_t mask); +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Disable(uint32_t mask); + +__STATIC_INLINE void ARM_PMU_CNTR_Increment(uint32_t mask); + +/** + \brief Enable the PMU +*/ +__STATIC_INLINE void ARM_PMU_Enable(void) +{ + PMU->CTRL |= PMU_CTRL_ENABLE_Msk; +} + +/** + \brief Disable the PMU +*/ +__STATIC_INLINE void ARM_PMU_Disable(void) +{ + PMU->CTRL &= ~PMU_CTRL_ENABLE_Msk; +} + +/** + \brief Set event to count for PMU eventer counter + \param [in] num Event counter (0-30) to configure + \param [in] type Event to count +*/ +__STATIC_INLINE void ARM_PMU_Set_EVTYPER(uint32_t num, uint32_t type) +{ + PMU->EVTYPER[num] = type; +} + +/** + \brief Reset cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CYCCNT_Reset(void) +{ + PMU->CTRL |= PMU_CTRL_CYCCNT_RESET_Msk; +} + +/** + \brief Reset all event counters +*/ +__STATIC_INLINE void ARM_PMU_EVCNTR_ALL_Reset(void) +{ + PMU->CTRL |= PMU_CTRL_EVENTCNT_RESET_Msk; +} + +/** + \brief Enable counters + \param [in] mask Counters to enable + \note Enables one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Enable(uint32_t mask) +{ + PMU->CNTENSET = mask; +} + +/** + \brief Disable counters + \param [in] mask Counters to enable + \note Disables one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Disable(uint32_t mask) +{ + PMU->CNTENCLR = mask; +} + +/** + \brief Read cycle counter + \return Cycle count +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_CCNTR(void) +{ + return PMU->CCNTR; +} + +/** + \brief Read event counter + \param [in] num Event counter (0-30) to read + \return Event count +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_EVCNTR(uint32_t num) +{ + return PMU->EVCNTR[num]; +} + +/** + \brief Read counter overflow status + \return Counter overflow status bits for the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_CNTR_OVS(void) +{ + return PMU->OVSSET; +} + +/** + \brief Clear counter overflow status + \param [in] mask Counter overflow status bits to clear + \note Clears overflow status bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_OVS(uint32_t mask) +{ + PMU->OVSCLR = mask; +} + +/** + \brief Enable counter overflow interrupt request + \param [in] mask Counter overflow interrupt request bits to set + \note Sets overflow interrupt request bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Enable(uint32_t mask) +{ + PMU->INTENSET = mask; +} + +/** + \brief Disable counter overflow interrupt request + \param [in] mask Counter overflow interrupt request bits to clear + \note Clears overflow interrupt request bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Disable(uint32_t mask) +{ + PMU->INTENCLR = mask; +} + +/** + \brief Software increment event counter + \param [in] mask Counters to increment + \note Software increment bits for one or more event counters (0-30) +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Increment(uint32_t mask) +{ + PMU->SWINC = mask; +} + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c new file mode 100644 index 0000000000..cf83d2e4cf --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c @@ -0,0 +1,439 @@ +/** + ************************************************************************** + * @file cdc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "cdc_class.h" +#include "cdc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_cdc_class + * @brief usb device class cdc demo + * @{ + */ + +/** @defgroup USB_cdc_class_private_functions + * @{ + */ + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc); +extern void usb_usart_config( linecoding_type linecoding); +static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len); + +linecoding_type linecoding = +{ + 115200, + 0, + 0, + 8 +}; + +/* cdc data struct */ +cdc_struct_type cdc_struct; + +/* usb device class handler */ +usbd_class_handler cdc_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &cdc_struct +}; +/** + * @brief initialize usb custom hid endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + /* init cdc struct */ + cdc_struct_init(pcdc); + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_CDC_INT_EPT, EPT_INT_TYPE, USBD_CDC_CMD_MAXPACKET_SIZE); + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_CDC_BULK_IN_EPT, EPT_BULK_TYPE, USBD_CDC_IN_MAXPACKET_SIZE); + + /* open out endpoint */ + usbd_ept_open(pudev, USBD_CDC_BULK_OUT_EPT, EPT_BULK_TYPE, USBD_CDC_OUT_MAXPACKET_SIZE); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_CDC_INT_EPT); + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_CDC_BULK_IN_EPT); + + /* close out endpoint */ + usbd_ept_close(pudev, USBD_CDC_BULK_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + if(setup->wLength) + { + if(setup->bmRequestType & USB_REQ_DIR_DTH) + { + usb_vcp_cmd_process(udev, setup->bRequest, pcdc->g_cmd, setup->wLength); + usbd_ctrl_send(pudev, pcdc->g_cmd, setup->wLength); + } + else + { + pcdc->g_req = setup->bRequest; + pcdc->g_len = setup->wLength; + usbd_ctrl_recv(pudev, pcdc->g_cmd, pcdc->g_len); + + } + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_ctrl_unsupport(pudev); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&pcdc->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + pcdc->alt_setting = setup->wValue; + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: usb device core handler type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + if( pcdc->g_req == SET_LINE_CODING) + { + /* class process */ + usb_vcp_cmd_process(udev, pcdc->g_req, pcdc->g_cmd, recv_len); + } + + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + usb_sts_type status = USB_OK; + + /* ...user code... + trans next packet data + */ + usbd_flush_tx_fifo(pudev, ept_num); + pcdc->g_tx_completed = 1; + + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + /* get endpoint receive data length */ + pcdc->g_rxlen = usbd_get_recv_len(pudev, ept_num); + + /*set recv flag*/ + pcdc->g_rx_completed = 1; + + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + usb_sts_type status = USB_OK; + UNUSED(udev); + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + case USBD_INISOINCOM_EVENT: + break; + case USBD_OUTISOINCOM_EVENT: + break; + + default: + break; + } + return status; +} + +/** + * @brief usb device cdc init + * @param pcdc: to the structure of cdc_struct + * @retval status of usb_sts_type + */ +static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc) +{ + pcdc->g_tx_completed = 1; + pcdc->g_rx_completed = 0; + pcdc->alt_setting = 0; + pcdc->linecoding.bitrate = linecoding.bitrate; + pcdc->linecoding.data = linecoding.data; + pcdc->linecoding.format = linecoding.format; + pcdc->linecoding.parity = linecoding.parity; + return USB_OK; +} + +/** + * @brief usb device class rx data process + * @param udev: to the structure of usbd_core_type + * @param recv_data: receive buffer + * @retval receive data len + */ +uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data) +{ + uint16_t i_index = 0; + uint16_t tmp_len = 0; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + if(pcdc->g_rx_completed == 0) + { + return 0; + } + pcdc->g_rx_completed = 0; + tmp_len = pcdc->g_rxlen; + for(i_index = 0; i_index < pcdc->g_rxlen; i_index ++) + { + recv_data[i_index] = pcdc->g_rx_buff[i_index]; + } + + usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE); + + return tmp_len; +} + +/** + * @brief usb device class send data + * @param udev: to the structure of usbd_core_type + * @param send_data: send data buffer + * @param len: send length + * @retval error status + */ +error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len) +{ + error_status status = SUCCESS; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + if(pcdc->g_tx_completed) + { + pcdc->g_tx_completed = 0; + usbd_ept_send(pudev, USBD_CDC_BULK_IN_EPT, send_data, len); + } + else + { + status = ERROR; + } + return status; +} + +/** + * @brief usb device function + * @param udev: to the structure of usbd_core_type + * @param cmd: request number + * @param buff: request buffer + * @param len: buffer length + * @retval none + */ +static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len) +{ + UNUSED(len); + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + switch(cmd) + { + case SET_LINE_CODING: + pcdc->linecoding.bitrate = (uint32_t)(buff[0] | (buff[1] << 8) | (buff[2] << 16) | (buff[3] <<24)); + pcdc->linecoding.format = buff[4]; + pcdc->linecoding.parity = buff[5]; + pcdc->linecoding.data = buff[6]; +#ifdef USB_VIRTUAL_COMPORT + /* set hardware usart */ + usb_usart_config(pcdc->linecoding); +#endif + break; + + case GET_LINE_CODING: + buff[0] = (uint8_t)pcdc->linecoding.bitrate; + buff[1] = (uint8_t)(pcdc->linecoding.bitrate >> 8); + buff[2] = (uint8_t)(pcdc->linecoding.bitrate >> 16); + buff[3] = (uint8_t)(pcdc->linecoding.bitrate >> 24); + buff[4] = (uint8_t)(pcdc->linecoding.format); + buff[5] = (uint8_t)(pcdc->linecoding.parity); + buff[6] = (uint8_t)(pcdc->linecoding.data); + break; + + default: + break; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h new file mode 100644 index 0000000000..be7e0b82af --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h @@ -0,0 +1,117 @@ +/** + ************************************************************************** + * @file cdc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc class file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CDC_CLASS_H +#define __CDC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_cdc_class + * @{ + */ + +/** @defgroup USB_cdc_class_definition + * @{ + */ + +/** + * @brief usb cdc use endpoint define + */ +#define USBD_CDC_INT_EPT 0x82 +#define USBD_CDC_BULK_IN_EPT 0x81 +#define USBD_CDC_BULK_OUT_EPT 0x01 + +/** + * @brief usb cdc in and out max packet size define + */ +#define USBD_CDC_IN_MAXPACKET_SIZE 0x40 +#define USBD_CDC_OUT_MAXPACKET_SIZE 0x40 +#define USBD_CDC_CMD_MAXPACKET_SIZE 0x08 + +/** + * @} + */ + +/** @defgroup USB_cdc_class_exported_types + * @{ + */ + +/** + * @brief usb cdc class struct + */ +typedef struct +{ + uint32_t alt_setting; + uint8_t g_rx_buff[USBD_CDC_OUT_MAXPACKET_SIZE]; + uint8_t g_cmd[USBD_CDC_CMD_MAXPACKET_SIZE]; + uint8_t g_req; + uint16_t g_len, g_rxlen; + __IO uint8_t g_tx_completed, g_rx_completed; + linecoding_type linecoding; +}cdc_struct_type; + + +/** + * @} + */ + +/** @defgroup USB_cdc_class_exported_functions + * @{ + */ +extern usbd_class_handler cdc_class_handler; +uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data); +error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c new file mode 100644 index 0000000000..bb268bf855 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c @@ -0,0 +1,446 @@ +/** + ************************************************************************** + * @file cdc_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "stdio.h" +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "cdc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_cdc_desc + * @brief usb device cdc descriptor + * @{ + */ + +/** @defgroup USB_cdc_desc_private_functions + * @{ + */ + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief device descriptor handler structure + */ +usbd_desc_handler cdc_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x02, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_CDC_VENDOR_ID), /* idVendor */ + HBYTE(USBD_CDC_VENDOR_ID), /* idVendor */ + LBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_CDC_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x02, /* bNumInterfaces: 2 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x00, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x01, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_CDC, /* bInterfaceClass: CDC class code */ + 0x02, /* bInterfaceSubClass: subclass code, Abstract Control Model*/ + 0x01, /* bInterfaceProtocol: protocol code, AT Command */ + 0x00, /* iInterface: index of string descriptor */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_HEADER, /* bDescriptorSubtype: Header function Descriptor 0x00*/ + LBYTE(CDC_BCD_NUM), + HBYTE(CDC_BCD_NUM), /* bcdCDC: USB class definitions for communications */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_CMF, /* bDescriptorSubtype: Call Management function descriptor subtype 0x01 */ + 0x00, /* bmCapabilities: 0x00*/ + 0x01, /* bDataInterface: interface number of data class interface optionally used for call management */ + + 0x04, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_ACM, /* bDescriptorSubtype: Abstract Control Management functional descriptor subtype 0x02 */ + 0x02, /* bmCapabilities: Support Set_Line_Coding and Get_Line_Coding 0x02 */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_UFD, /* bDescriptorSubtype: Union Function Descriptor subtype 0x06 */ + 0x00, /* bControlInterface: The interface number of the communications or data class interface 0x00 */ + 0x01, /* bSubordinateInterface0: interface number of first subordinate interface in the union */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_INT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_CMD_MAXPACKET_SIZE), + HBYTE(USBD_CDC_CMD_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + CDC_HID_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ + + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x01, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_CDCDATA, /* bInterfaceClass: CDC-data class code */ + 0x00, /* bInterfaceSubClass: Data interface subclass code 0x00*/ + 0x00, /* bInterfaceProtocol: data class protocol code 0x00 */ + 0x00, /* iInterface: index of string descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_BULK_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_IN_MAXPACKET_SIZE), + HBYTE(USBD_CDC_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_BULK_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_OUT_MAXPACKET_SIZE), + HBYTE(USBD_CDC_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_CDC_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_CDC_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_CDC_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_CDC_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_CDC_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_CDC_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_CDC_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = (uint8_t)str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h new file mode 100644 index 0000000000..dd406f720b --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h @@ -0,0 +1,104 @@ +/** + ************************************************************************** + * @file cdc_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CDC_DESC_H +#define __CDC_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "cdc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_cdc_desc + * @{ + */ + +/** @defgroup USB_cdc_desc_definition + * @{ + */ +/** + * @brief usb bcd number define + */ +#define CDC_BCD_NUM 0x0110 + +/** + * @brief usb vendor id and product id define + */ +#define USBD_CDC_VENDOR_ID 0x2E3C +#define USBD_CDC_PRODUCT_ID 0x5740 + +/** + * @brief usb descriptor size define + */ +#define USBD_CDC_CONFIG_DESC_SIZE 67 +#define USBD_CDC_SIZ_STRING_LANGID 4 +#define USBD_CDC_SIZ_STRING_SERIAL 0x1A + +/** + * @brief usb string define(vendor, product configuration, interface) + */ +#define USBD_CDC_DESC_MANUFACTURER_STRING "Artery" +#define USBD_CDC_DESC_PRODUCT_STRING "AT32 Virtual Com Port " +#define USBD_CDC_DESC_CONFIGURATION_STRING "Virtual ComPort Config" +#define USBD_CDC_DESC_INTERFACE_STRING "Virtual ComPort Interface" + +/** + * @brief usb endpoint interval define + */ +#define CDC_HID_BINTERVAL_TIME 0xFF + +/** + * @brief usb mcu id address deine + */ +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) +/** + * @} + */ + +extern usbd_desc_handler cdc_desc_handler; + + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c new file mode 100644 index 0000000000..ea2c9810e3 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c @@ -0,0 +1,342 @@ +/** + ************************************************************************** + * @file hid_iap_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "hid_iap_class.h" +#include "hid_iap_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_hid_iap_class + * @brief usb device class hid iap demo + * @{ + */ + +/** @defgroup USB_hid_iap_class_private_functions + * @{ + */ + + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +iap_info_type iap_info; + +/* usb device class handler */ +usbd_class_handler hid_iap_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &iap_info +}; + +/** + * @brief initialize usb custom hid endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + /* open hid iap in endpoint */ + usbd_ept_open(pudev, USBD_HIDIAP_IN_EPT, EPT_INT_TYPE, USBD_HIDIAP_IN_MAXPACKET_SIZE); + + /* open hid iap out endpoint */ + usbd_ept_open(pudev, USBD_HIDIAP_OUT_EPT, EPT_INT_TYPE, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_HIDIAP_OUT_EPT, piap->g_rxhid_buff, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close hid iap in endpoint */ + usbd_ept_close(pudev, USBD_HIDIAP_IN_EPT); + + /* close hid iap out endpoint */ + usbd_ept_close(pudev, USBD_HIDIAP_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + uint16_t len; + uint8_t *buf; + + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + switch(setup->bRequest) + { + case HID_REQ_SET_PROTOCOL: + piap->hid_protocol = (uint8_t)setup->wValue; + break; + case HID_REQ_GET_PROTOCOL: + usbd_ctrl_send(pudev, (uint8_t *)&piap->hid_protocol, 1); + break; + case HID_REQ_SET_IDLE: + piap->hid_set_idle = (uint8_t)(setup->wValue >> 8); + break; + case HID_REQ_GET_IDLE: + usbd_ctrl_send(pudev, (uint8_t *)&piap->hid_set_idle, 1); + break; + case HID_REQ_SET_REPORT: + piap->hid_state = HID_REQ_SET_REPORT; + usbd_ctrl_recv(pudev, piap->hid_set_report, setup->wLength); + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + if(setup->wValue >> 8 == HID_REPORT_DESC) + { + len = MIN(USBD_HIDIAP_SIZ_REPORT_DESC, setup->wLength); + buf = (uint8_t *)g_usbd_hidiap_report; + } + else if(setup->wValue >> 8 == HID_DESCRIPTOR_TYPE) + { + len = MIN(9, setup->wLength); + buf = (uint8_t *)g_hidiap_usb_desc; + } + usbd_ctrl_send(pudev, (uint8_t *)buf, len); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&piap->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + piap->alt_setting = setup->wValue; + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + if( piap->hid_state == HID_REQ_SET_REPORT) + { + /* hid buffer process */ + piap->hid_state = 0; + } + + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + + /* ...user code... + trans next packet data + */ + usbd_hid_iap_in_complete(udev); + + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + + /* get endpoint receive data length */ + uint32_t recv_len = usbd_get_recv_len(pudev, ept_num); + + /* hid iap process */ + usbd_hid_iap_process(udev, piap->g_rxhid_buff, recv_len); + + /* start receive next packet */ + usbd_ept_recv(pudev, USBD_HIDIAP_OUT_EPT, piap->g_rxhid_buff, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + usb_sts_type status = USB_OK; + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + default: + break; + } + return status; +} + +/** + * @brief usb device class send report + * @param udev: to the structure of usbd_core_type + * @param report: report buffer + * @param len: report length + * @retval status of usb_sts_type + */ +usb_sts_type usb_iap_class_send_report(void *udev, uint8_t *report, uint16_t len) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + if(usbd_connect_state_get(pudev) == USB_CONN_STATE_CONFIGURED) + usbd_ept_send(pudev, USBD_HIDIAP_IN_EPT, report, len); + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h new file mode 100644 index 0000000000..00d6d7b5a0 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h @@ -0,0 +1,159 @@ +/** + ************************************************************************** + * @file hid_iap_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __HID_IAP_CLASS_H +#define __HID_IAP_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_hid_iap_class + * @{ + */ + +/** @defgroup USB_hid_iap_class_definition + * @{ + */ + + +#define USBD_HIDIAP_IN_EPT 0x81 +#define USBD_HIDIAP_OUT_EPT 0x01 + +#define USBD_HIDIAP_IN_MAXPACKET_SIZE 0x40 +#define USBD_HIDIAP_OUT_MAXPACKET_SIZE 0x40 + +#define FLASH_SIZE_REG() ((*(uint32_t *)0x1FFFF7E0) & 0xFFFF) /*Get Flash size*/ +#define KB_TO_B(kb) ((kb) << 10) + +#define SECTOR_SIZE_1K 0x400 +#define SECTOR_SIZE_2K 0x800 +#define SECTOR_SIZE_4K 0x1000 + +/** + * @brief iap command + */ +#define IAP_CMD_IDLE 0x5AA0 +#define IAP_CMD_START 0x5AA1 +#define IAP_CMD_ADDR 0x5AA2 +#define IAP_CMD_DATA 0x5AA3 +#define IAP_CMD_FINISH 0x5AA4 +#define IAP_CMD_CRC 0x5AA5 +#define IAP_CMD_JMP 0x5AA6 +#define IAP_CMD_GET 0x5AA7 + +#define HID_IAP_BUFFER_LEN 1024 +#define IAP_UPGRADE_COMPLETE_FLAG 0x41544B38 +#define CONVERT_ENDIAN(dwValue) ((dwValue >> 24) | ((dwValue >> 8) & 0xFF00) | \ + ((dwValue << 8) & 0xFF0000) | (dwValue << 24) ) + +#define IAP_ACK 0xFF00 +#define IAP_NACK 0x00FF + +typedef enum +{ + IAP_SUCCESS, + IAP_WAIT, + IAP_FAILED +}iap_result_type; + +typedef enum +{ + IAP_STS_IDLE, + IAP_STS_START, + IAP_STS_ADDR, + IAP_STS_DATA, + IAP_STS_FINISH, + IAP_STS_CRC, + IAP_STS_JMP_WAIT, + IAP_STS_JMP, +}iap_machine_state_type; + +typedef struct +{ + + uint8_t iap_fifo[HID_IAP_BUFFER_LEN]; + uint8_t iap_rx[USBD_HIDIAP_OUT_MAXPACKET_SIZE]; + uint8_t iap_tx[USBD_HIDIAP_IN_MAXPACKET_SIZE]; + + uint32_t fifo_length; + uint32_t tx_length; + + uint32_t app_address; + uint32_t iap_address; + uint32_t flag_address; + + uint32_t flash_start_address; + uint32_t flash_end_address; + + uint32_t sector_size; + uint32_t flash_size; + + uint32_t respond_flag; + + uint8_t g_rxhid_buff[USBD_HIDIAP_OUT_MAXPACKET_SIZE]; + uint32_t hid_protocol; + uint32_t hid_set_idle; + uint32_t alt_setting; + uint32_t hid_state; + uint8_t hid_set_report[64]; + + iap_machine_state_type state; +}iap_info_type; + +extern usbd_class_handler hid_iap_class_handler; +extern iap_info_type iap_info; +usb_sts_type usb_iap_class_send_report(void *udev, uint8_t *report, uint16_t len); +iap_result_type usbd_hid_iap_process(void *udev, uint8_t *report, uint16_t len); +void usbd_hid_iap_in_complete(void *udev); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c new file mode 100644 index 0000000000..4cab141e45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c @@ -0,0 +1,468 @@ +/** + ************************************************************************** + * @file hid_iap_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "hid_iap_desc.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_hid_iap_desc + * @brief usb device hid_iap descriptor + * @{ + */ + +/** @defgroup USB_hid_iap_desc_private_functions + * @{ + */ + + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief hid device descriptor handler structure + */ +usbd_desc_handler hid_iap_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x00, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_HIDIAP_VENDOR_ID), /* idVendor */ + HBYTE(USBD_HIDIAP_VENDOR_ID), /* idVendor */ + LBYTE(USBD_HIDIAP_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_HIDIAP_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_HIDIAP_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_HIDIAP_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_HIDIAP_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x01, /* bNumInterfaces: 1 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x00, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_HID, /* bInterfaceClass: class code hid */ + 0x00, /* bInterfaceSubClass: subclass code */ + 0x00, /* bInterfaceProtocol: protocol code */ + 0x00, /* iInterface: index of string descriptor */ + + 0x09, /* bLength: size of HID descriptor in bytes */ + HID_CLASS_DESC_HID, /* bDescriptorType: HID descriptor type */ + LBYTE(HIDIAP_BCD_NUM), + HBYTE(HIDIAP_BCD_NUM), /* bcdHID: HID class specification release number */ + 0x00, /* bCountryCode: hardware target conutry */ + 0x01, /* bNumDescriptors: number of HID class descriptor to follow */ + HID_CLASS_DESC_REPORT, /* bDescriptorType: report descriptor type */ + LBYTE(sizeof(g_usbd_hidiap_report)), + HBYTE(sizeof(g_usbd_hidiap_report)), /* wDescriptorLength: total length of reprot descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_HIDIAP_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_HIDIAP_IN_MAXPACKET_SIZE), + HBYTE(USBD_HIDIAP_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + HIDIAP_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_HIDIAP_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_HIDIAP_OUT_MAXPACKET_SIZE), + HBYTE(USBD_HIDIAP_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + HIDIAP_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb hid report descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t g_usbd_hidiap_report[USBD_HIDIAP_SIZ_REPORT_DESC] ALIGNED_TAIL = +{ + 0x06, 0xFF, 0x00, /* USAGE_PAGE(Vendor Page:0xFF00) */ + 0x09, 0x01, /* USAGE (Demo Kit) */ + 0xa1, 0x01, /* COLLECTION (Application) */ + + /* 6 */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0xFF, /* LOGICAL_MAXIMUM (255) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x40, /* REPORT_COUNT (64) */ + + 0x09, 0x01, + 0x81, 0x02, + 0x95, 0x40, + + 0x09, 0x01, + 0x91, 0x02, + 0x95, 0x01, + + 0x09, 0x01, + 0xB1, 0x02, + 0xC0 +}; + +/** + * @brief usb hid descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t g_hidiap_usb_desc[9] ALIGNED_TAIL = +{ + 0x09, /* bLength: size of HID descriptor in bytes */ + HID_CLASS_DESC_HID, /* bDescriptorType: HID descriptor type */ + LBYTE(HIDIAP_BCD_NUM), + HBYTE(HIDIAP_BCD_NUM), /* bcdHID: HID class specification release number */ + 0x00, /* bCountryCode: hardware target conutry */ + 0x01, /* bNumDescriptors: number of HID class descriptor to follow */ + HID_CLASS_DESC_REPORT, /* bDescriptorType: report descriptor type */ + LBYTE(sizeof(g_usbd_hidiap_report)), + HBYTE(sizeof(g_usbd_hidiap_report)), /* wDescriptorLength: total length of reprot descriptor */ +}; + + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_HIDIAP_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_HIDIAP_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_HIDIAP_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_HIDIAP_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_HIDIAP_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_HIDIAP_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_HIDIAP_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h new file mode 100644 index 0000000000..ef3b76e435 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h @@ -0,0 +1,94 @@ +/** + ************************************************************************** + * @file hid_iap_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __HID_IAP_DESC_H +#define __HID_IAP_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "hid_iap_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_hid_iap_desc + * @{ + */ + +/** @defgroup USB_hid_iap_desc_definition + * @{ + */ + + +#define HIDIAP_BCD_NUM 0x0110 + +#define USBD_HIDIAP_VENDOR_ID 0x2E3C +#define USBD_HIDIAP_PRODUCT_ID 0xAF01 + +#define USBD_HIDIAP_CONFIG_DESC_SIZE 41 +#define USBD_HIDIAP_SIZ_REPORT_DESC 32 +#define USBD_HIDIAP_SIZ_STRING_LANGID 4 +#define USBD_HIDIAP_SIZ_STRING_SERIAL 0x1A + +#define USBD_HIDIAP_DESC_MANUFACTURER_STRING "Artery" +#define USBD_HIDIAP_DESC_PRODUCT_STRING "HID IAP" +#define USBD_HIDIAP_DESC_CONFIGURATION_STRING "HID IAP Config" +#define USBD_HIDIAP_DESC_INTERFACE_STRING "HID IAP Interface" + +#define HIDIAP_BINTERVAL_TIME 0x01 + +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) +extern uint8_t g_usbd_hidiap_report[USBD_HIDIAP_SIZ_REPORT_DESC]; +extern uint8_t g_hidiap_usb_desc[9]; + +extern usbd_desc_handler hid_iap_desc_handler; + + +/** + * @} + */ + +/** + * @} + */ + + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c new file mode 100644 index 0000000000..0a458cd5ca --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c @@ -0,0 +1,835 @@ +/** + ************************************************************************** + * @file msc_bot_scsi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb mass storage bulk-only transport and scsi command + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "msc_bot_scsi.h" +#include "msc/at32_msc_diskio.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_bot_scsi + * @brief usb device class mass storage demo + * @{ + */ + +/** @defgroup USB_msc_bot_functions + * @{ + */ + + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t page00_inquiry_data[] ALIGNED_TAIL = { + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + +}; +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD sense_type sense_data ALIGNED_TAIL = +{ + 0x70, + 0x00, + SENSE_KEY_ILLEGAL_REQUEST, + 0x00000000, + 0x0A, + 0x00000000, + 0x20, + 0x00, + 0x00000000 +}; + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t mode_sense6_data[8] ALIGNED_TAIL = +{ + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00 +}; + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t mode_sense10_data[8] ALIGNED_TAIL = +{ + 0x00, + 0x06, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00 +}; +/** + * @brief initialize bulk-only transport and scsi + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_init(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + pmsc->bot_status = MSC_BOT_STATE_IDLE; + pmsc->max_lun = MSC_SUPPORT_MAX_LUN - 1; + + pmsc->csw_struct.dCSWSignature = CSW_DCSWSIGNATURE; + pmsc->csw_struct.dCSWDataResidue = 0; + pmsc->csw_struct.dCSWSignature = 0; + pmsc->csw_struct.dCSWTag = CSW_BCSWSTATUS_PASS; + + usbd_flush_tx_fifo(pudev, USBD_MSC_BULK_IN_EPT&0x7F); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + +/** + * @brief reset bulk-only transport and scsi + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_reset(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + pmsc->bot_status = MSC_BOT_STATE_RECOVERY; + pmsc->max_lun = MSC_SUPPORT_MAX_LUN - 1; + usbd_flush_tx_fifo(pudev, USBD_MSC_BULK_IN_EPT&0x7F); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + +/** + * @brief bulk-only transport data in handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void bot_scsi_datain_handler(void *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->msc_state) + { + case MSC_STATE_MACHINE_DATA_IN: + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } + break; + + case MSC_STATE_MACHINE_LAST_DATA: + case MSC_STATE_MACHINE_SEND_DATA: + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + break; + + default: + break; + } +} + +/** + * @brief bulk-only transport data out handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void bot_scsi_dataout_handler(void *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->msc_state) + { + case MSC_STATE_MACHINE_IDLE: + bot_cbw_decode(udev); + break; + + case MSC_STATE_MACHINE_DATA_OUT: + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } + break; + } +} + +/** + * @brief bulk-only cbw decode + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_cbw_decode(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + pmsc->csw_struct.dCSWTag = pmsc->cbw_struct.dCBWTage; + pmsc->csw_struct.dCSWDataResidue = pmsc->cbw_struct.dCBWDataTransferLength; + + /* check param */ + if((pmsc->cbw_struct.dCBWSignature != CBW_DCBWSIGNATURE) || + (usbd_get_recv_len(pudev, USBD_MSC_BULK_OUT_EPT) != CBW_CMD_LENGTH) + || (pmsc->cbw_struct.bCBWLUN > MSC_SUPPORT_MAX_LUN) || + (pmsc->cbw_struct.bCBWCBLength < 1) || (pmsc->cbw_struct.bCBWCBLength > 16)) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + pmsc->bot_status = MSC_BOT_STATE_ERROR; + bot_scsi_stall(udev); + } + else + { + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_stall(udev); + } + else if((pmsc->msc_state != MSC_STATE_MACHINE_DATA_IN) && + (pmsc->msc_state != MSC_STATE_MACHINE_DATA_OUT) && + (pmsc->msc_state != MSC_STATE_MACHINE_LAST_DATA)) + { + if(pmsc->data_len == 0) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + } + else if(pmsc->data_len > 0) + { + bot_scsi_send_data(udev, pmsc->data, pmsc->data_len); + } + } + } +} + +/** + * @brief send bot data + * @param udev: to the structure of usbd_core_type + * @param buffer: data buffer + * @param len: data len + * @retval none + */ +void bot_scsi_send_data(void *udev, uint8_t *buffer, uint32_t len) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint32_t data_len = MIN(len, pmsc->cbw_struct.dCBWDataTransferLength); + + pmsc->csw_struct.dCSWDataResidue -= data_len; + pmsc->csw_struct.bCSWStatus = CSW_BCSWSTATUS_PASS; + + pmsc->msc_state = MSC_STATE_MACHINE_SEND_DATA; + + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, + buffer, data_len); +} + +/** + * @brief send command status + * @param udev: to the structure of usbd_core_type + * @param status: csw status + * @retval none + */ +void bot_scsi_send_csw(void *udev, uint8_t status) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + pmsc->csw_struct.bCSWStatus = status; + pmsc->csw_struct.dCSWSignature = CSW_DCSWSIGNATURE; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, + (uint8_t *)&pmsc->csw_struct, CSW_CMD_LENGTH); + + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, + (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + + +/** + * @brief send scsi sense code + * @param udev: to the structure of usbd_core_type + * @param sense_key: sense key + * @param asc: asc + * @retval none + */ +void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc) +{ + UNUSED(udev); + sense_data.sense_key = sense_key; + sense_data.asc = asc; +} + + +/** + * @brief check address + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @param blk_offset: blk offset address + * @param blk_count: blk number + * @retval usb_sts_type + */ +usb_sts_type bot_scsi_check_address(void *udev, uint8_t lun, uint32_t blk_offset, uint32_t blk_count) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + if((blk_offset + blk_count) > pmsc->blk_nbr[lun]) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); + return USB_FAIL; + } + return USB_OK; +} + +/** + * @brief bot endpoint stall + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_stall(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if((pmsc->cbw_struct.dCBWDataTransferLength != 0) && + (pmsc->cbw_struct.bmCBWFlags == 0) && + pmsc->bot_status == MSC_BOT_STATE_IDLE) + { + usbd_set_stall(pudev, USBD_MSC_BULK_OUT_EPT); + } + usbd_set_stall(pudev, USBD_MSC_BULK_IN_EPT); + + if(pmsc->bot_status == MSC_BOT_STATE_ERROR) + { + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, + (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); + } +} + +/** + * @brief bulk-only transport scsi command test unit + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun) +{ + UNUSED(lun); + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if(pmsc->cbw_struct.dCBWDataTransferLength != 0) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->data_len = 0; + return status; +} + +/** + * @brief bulk-only transport scsi command inquiry + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun) +{ + uint8_t *pdata; + uint32_t trans_len = 0; + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if(pmsc->cbw_struct.CBWCB[1] & 0x01) + { + pdata = page00_inquiry_data; + trans_len = 5; + } + else + { + pdata = get_inquiry(lun); + if(pmsc->cbw_struct.dCBWDataTransferLength < SCSI_INQUIRY_DATA_LENGTH) + { + trans_len = pmsc->cbw_struct.dCBWDataTransferLength; + } + else + { + trans_len = SCSI_INQUIRY_DATA_LENGTH; + } + } + + pmsc->data_len = trans_len; + while(trans_len) + { + trans_len --; + pmsc->data[trans_len] = pdata[trans_len]; + } + return status; +} + +/** + * @brief bulk-only transport scsi command start stop + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun) +{ + UNUSED(lun); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command meidum removal + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun) +{ + UNUSED(lun); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command mode sense6 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint8_t data_len = 8; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 8; + while(data_len) + { + data_len --; + pmsc->data[data_len] = mode_sense6_data[data_len]; + }; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command mode sense10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint8_t data_len = 8; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 8; + while(data_len) + { + data_len --; + pmsc->data[data_len] = mode_sense10_data[data_len]; + }; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command capacity + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_capacity(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + msc_disk_capacity(lun, &pmsc->blk_nbr[lun], &pmsc->blk_size[lun]); + + pdata[0] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 24); + pdata[1] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 16); + pdata[2] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 8); + pdata[3] = (uint8_t)((pmsc->blk_nbr[lun] - 1)); + + pdata[4] = (uint8_t)((pmsc->blk_size[lun]) >> 24); + pdata[5] = (uint8_t)((pmsc->blk_size[lun]) >> 16); + pdata[6] = (uint8_t)((pmsc->blk_size[lun]) >> 8); + pdata[7] = (uint8_t)((pmsc->blk_size[lun])); + + pmsc->data_len = 8; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command format capacity + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + + pdata[0] = 0; + pdata[1] = 0; + pdata[2] = 0; + pdata[3] = 0x08; + + msc_disk_capacity(lun, &pmsc->blk_nbr[lun], &pmsc->blk_size[lun]); + + pdata[4] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 24); + pdata[5] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 16); + pdata[6] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 8); + pdata[7] = (uint8_t)((pmsc->blk_nbr[lun] - 1)); + + pdata[8] = 0x02; + + pdata[9] = (uint8_t)((pmsc->blk_size[lun]) >> 16); + pdata[10] = (uint8_t)((pmsc->blk_size[lun]) >> 8); + pdata[11] = (uint8_t)((pmsc->blk_size[lun])); + + pmsc->data_len = 12; + + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command request sense + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint32_t trans_len = 0x12; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + uint8_t *sdata = (uint8_t *)&sense_data; + + while(trans_len) + { + trans_len --; + pdata[trans_len] = sdata[trans_len]; + } + + if(pmsc->cbw_struct.dCBWDataTransferLength < REQ_SENSE_STANDARD_DATA_LEN) + { + pmsc->data_len = pmsc->cbw_struct.dCBWDataTransferLength; + } + else + { + pmsc->data_len = REQ_SENSE_STANDARD_DATA_LEN; + } + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command verify + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_verify(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + if((pmsc->cbw_struct.CBWCB[1] & 0x02) == 0x02) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command read10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_read10(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + uint32_t len; + + if(pmsc->msc_state == MSC_STATE_MACHINE_IDLE) + { + if((pmsc->cbw_struct.bmCBWFlags & 0x80) != 0x80) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + + pmsc->blk_addr *= pmsc->blk_size[lun]; + pmsc->blk_len *= pmsc->blk_size[lun]; + + if(pmsc->cbw_struct.dCBWDataTransferLength != pmsc->blk_len) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + pmsc->msc_state = MSC_STATE_MACHINE_DATA_IN; + } + pmsc->data_len = MSC_MAX_DATA_BUF_LEN; + + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + if( msc_disk_read(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK) + { + bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT); + return USB_FAIL; + } + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, pmsc->data, len); + pmsc->blk_addr += len; + pmsc->blk_len -= len; + + pmsc->csw_struct.dCSWDataResidue -= len; + if(pmsc->blk_len == 0) + { + pmsc->msc_state = MSC_STATE_MACHINE_LAST_DATA; + } + + return USB_OK; +} + + +/** + * @brief bulk-only transport scsi command write10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_write10(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + uint32_t len; + + if(pmsc->msc_state == MSC_STATE_MACHINE_IDLE) + { + if((pmsc->cbw_struct.bmCBWFlags & 0x80) == 0x80) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + + pmsc->blk_addr *= pmsc->blk_size[lun]; + pmsc->blk_len *= pmsc->blk_size[lun]; + + if(pmsc->cbw_struct.dCBWDataTransferLength != pmsc->blk_len) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->msc_state = MSC_STATE_MACHINE_DATA_OUT; + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)pmsc->data, len); + + } + else + { + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + if(msc_disk_write(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK) + { + bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT); + return USB_FAIL; + } + + pmsc->blk_addr += len; + pmsc->blk_len -= len; + + pmsc->csw_struct.dCSWDataResidue -= len; + + if(pmsc->blk_len == 0) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + } + else + { + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)pmsc->data, len); + } + } + return USB_OK; +} + +/** + * @brief clear feature + * @param udev: to the structure of usbd_core_type + * @param etp_num: endpoint number + * @retval status of usb_sts_type + */ +void bot_scsi_clear_feature(void *udev, uint8_t ept_num) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + if(pmsc->bot_status == MSC_BOT_STATE_ERROR) + { + usbd_set_stall(pudev, USBD_MSC_BULK_IN_EPT); + pmsc->bot_status = MSC_BOT_STATE_IDLE; + } + else if(((ept_num & 0x80) == 0x80) && (pmsc->bot_status != MSC_BOT_STATE_RECOVERY)) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } +} + +/** + * @brief bulk-only transport scsi command process + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_cmd_process(void *udev) +{ + usb_sts_type status = USB_FAIL; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->cbw_struct.CBWCB[0]) + { + case MSC_CMD_INQUIRY: + status = bot_scsi_inquiry(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_START_STOP: + status = bot_scsi_start_stop(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_MODE_SENSE6: + status = bot_scsi_mode_sense6(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_MODE_SENSE10: + status = bot_scsi_mode_sense10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_ALLOW_MEDIUM_REMOVAL: + status = bot_scsi_allow_medium_removal(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_10: + status = bot_scsi_read10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_CAPACITY: + status = bot_scsi_capacity(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_REQUEST_SENSE: + status = bot_scsi_request_sense(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_TEST_UNIT: + status = bot_scsi_test_unit(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_VERIFY: + status = bot_scsi_verify(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_WRITE_10: + status = bot_scsi_write10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_FORMAT_CAPACITY: + status = bot_scsi_format_capacity(udev, pmsc->cbw_struct.bCBWLUN); + break; + + default: + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + status = USB_FAIL; + break; + } + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h new file mode 100644 index 0000000000..0c3948268e --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h @@ -0,0 +1,256 @@ +/** + ************************************************************************** + * @file msc_bot_scsi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb mass storage bulk-only transport and scsi command header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_BOT_SCSI_H +#define __MSC_BOT_SCSI_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "msc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_bot_scsi + * @{ + */ + +/** @defgroup USB_msc_bot_scsi_definition + * @{ + */ + +#define MSC_SUPPORT_MAX_LUN 1 +#define MSC_MAX_DATA_BUF_LEN 4096 + +#define MSC_CMD_FORMAT_UNIT 0x04 +#define MSC_CMD_INQUIRY 0x12 +#define MSC_CMD_START_STOP 0x1B +#define MSC_CMD_MODE_SENSE6 0x1A +#define MSC_CMD_MODE_SENSE10 0x5A +#define MSC_CMD_ALLOW_MEDIUM_REMOVAL 0x1E +#define MSC_CMD_READ_10 0x28 +#define MSC_CMD_READ_12 0xA8 +#define MSC_CMD_READ_CAPACITY 0x25 +#define MSC_CMD_READ_FORMAT_CAPACITY 0x23 +#define MSC_CMD_REQUEST_SENSE 0x03 +#define MSC_CMD_TEST_UNIT 0x00 +#define MSC_CMD_VERIFY 0x2F +#define MSC_CMD_WRITE_10 0x2A +#define MSC_CMD_WRITE_12 0xAA +#define MSC_CMD_WRITE_VERIFY 0x2E + +#define MSC_REQ_GET_MAX_LUN 0xFE /*!< get max lun */ +#define MSC_REQ_BO_RESET 0xFF /*!< bulk only mass storage reset */ + +#define SET_LINE_CODING 0x20 +#define GET_LINE_CODING 0x21 + +#define CBW_CMD_LENGTH 31 +#define CBW_DCBWSIGNATURE 0x43425355 +#define CBW_BMCBWFLAGS_DIR_OUT 0x00 +#define CBW_BMCBWFLAGS_DIR_IN 0x80 + +#define CSW_CMD_LENGTH 13 +#define CSW_DCSWSIGNATURE 0x53425355 +#define CSW_BCSWSTATUS_PASS 0x00 +#define CSW_BCSWSTATUS_FAILED 0x01 +#define CSW_BCSWSTATUS_PHASE_ERR 0x02 + +#define MSC_STATE_MACHINE_CMD 0x00 +#define MSC_STATE_MACHINE_DATA_IN 0x01 +#define MSC_STATE_MACHINE_DATA_OUT 0x02 +#define MSC_STATE_MACHINE_SEND_DATA 0x03 +#define MSC_STATE_MACHINE_LAST_DATA 0x04 +#define MSC_STATE_MACHINE_STATUS 0x05 +#define MSC_STATE_MACHINE_FAILED 0x06 +#define MSC_STATE_MACHINE_IDLE 0x07 + +#define MSC_BOT_STATE_IDLE 0x00 +#define MSC_BOT_STATE_RECOVERY 0x01 +#define MSC_BOT_STATE_ERROR 0x02 + +#define REQ_SENSE_STANDARD_DATA_LEN 0x12 +#define SENSE_KEY_NO_SENSE 0x00 +#define SENSE_KEY_RECOVERED_ERROR 0x01 +#define SENSE_KEY_NOT_READY 0x02 +#define SENSE_KEY_MEDIUM_ERROR 0x03 +#define SENSE_KEY_HARDWARE_ERROR 0x04 +#define SENSE_KEY_ILLEGAL_REQUEST 0x05 +#define SENSE_KEY_UNIT_ATTENTION 0x06 +#define SENSE_KEY_DATA_PROTECT 0x07 +#define SENSE_KEY_BLANK_CHECK 0x08 +#define SENSE_KEY_VENDERO_SPECIFIC 0x09 +#define SENSE_KEY_ABORTED_COMMAND 0x0B +#define SENSE_KEY_VOLUME_OVERFLOW 0x0D +#define SENSE_KEY_MISCOMPARE 0x0E + + +#define INVALID_COMMAND 0x20 +#define INVALID_FIELED_IN_COMMAND 0x24 +#define PARAMETER_LIST_LENGTH_ERROR 0x1A +#define INVALID_FIELD_IN_PARAMETER_LIST 0x26 +#define ADDRESS_OUT_OF_RANGE 0x21 +#define MEDIUM_NOT_PRESENT 0x3A +#define MEDIUM_HAVE_CHANGED 0x28 + +#define SCSI_INQUIRY_DATA_LENGTH 36 + +/** + * @brief typical command block description + */ +typedef struct +{ + uint8_t opcode; + uint8_t lun; + uint32_t address; + uint8_t reserved1; + uint32_t alloc_length; + uint16_t reserved2; +}cbd_typical_type; + +/** + * @brief extended command block description + */ +typedef struct +{ + uint8_t opcode; + uint8_t lun; + uint32_t address; + uint8_t reserved1; + uint32_t alloc_length; + uint16_t reserved2; +}cbd_extended_type; + +/** + * @brief command block wrapper + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTage; + uint32_t dCBWDataTransferLength; + uint8_t bmCBWFlags; + uint8_t bCBWLUN; + uint8_t bCBWCBLength; + uint8_t CBWCB[16]; +}cbw_type; + +/** + * @brief command block wrapper + */ +typedef struct +{ + uint32_t dCSWSignature; + uint32_t dCSWTag; + uint32_t dCSWDataResidue; + uint32_t bCSWStatus; +}csw_type; + +/** + * @brief request sense standard data + */ +typedef struct +{ + uint8_t err_code; + uint8_t reserved1; + uint8_t sense_key; + uint32_t information; + uint8_t as_length; + uint32_t reserved2; + uint8_t asc; + uint8_t ascq; + uint32_t reserved3; +}sense_type; + + +typedef struct +{ + uint8_t msc_state; + uint8_t bot_status; + uint32_t max_lun; + + uint32_t blk_nbr[MSC_SUPPORT_MAX_LUN]; + uint32_t blk_size[MSC_SUPPORT_MAX_LUN]; + + uint32_t blk_addr; + uint32_t blk_len; + + uint32_t data_len; + uint8_t data[MSC_MAX_DATA_BUF_LEN]; + + uint32_t alt_setting; + + cbw_type cbw_struct; + csw_type csw_struct; + +}msc_type; + +void bot_scsi_init(void *udev); +void bot_scsi_reset(void *udev); +void bot_scsi_datain_handler(void *pudev, uint8_t ept_num); +void bot_scsi_dataout_handler(void *pudev, uint8_t ept_num); +void bot_cbw_decode(void *udev); +void bot_scsi_send_data(void *udev, uint8_t *buffer, uint32_t len); +void bot_scsi_send_csw(void *udev, uint8_t status); +void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc); +usb_sts_type bot_scsi_check_address(void *udev, uint8_t lun, uint32_t blk_offset, uint32_t blk_count); +void bot_scsi_stall(void *udev); +usb_sts_type bot_scsi_cmd_process(void *udev); + +usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun); +usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun); +usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun); +usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun); +usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun); +usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun); +usb_sts_type bot_scsi_read10(void *udev, uint8_t lun); +usb_sts_type bot_scsi_capacity(void *udev, uint8_t lun); +usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun); +usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun); +usb_sts_type bot_scsi_verify(void *udev, uint8_t lun); +usb_sts_type bot_scsi_write10(void *udev, uint8_t lun); +void bot_scsi_clear_feature(void *udev, uint8_t ept_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c new file mode 100644 index 0000000000..d9418a9c45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c @@ -0,0 +1,298 @@ +/** + ************************************************************************** + * @file msc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "msc_class.h" +#include "msc_desc.h" +#include "msc_bot_scsi.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_class + * @brief usb device class msc demo + * @{ + */ + +/** @defgroup USB_msc_class_private_functions + * @{ + */ + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +msc_type msc_struct; + +/* usb device class handler */ +usbd_class_handler msc_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &msc_struct +}; + +/** + * @brief initialize usb endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_MSC_BULK_IN_EPT, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + + /* open out endpoint */ + usbd_ept_open(pudev, USBD_MSC_BULK_OUT_EPT, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + + bot_scsi_init(udev); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_MSC_BULK_IN_EPT); + + /* close out endpoint */ + usbd_ept_close(pudev, USBD_MSC_BULK_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + + switch(setup->bRequest) + { + case MSC_REQ_GET_MAX_LUN: + usbd_ctrl_send(pudev, (uint8_t *)&pmsc->max_lun, 1); + break; + case MSC_REQ_BO_RESET: + bot_scsi_reset(udev); + usbd_ctrl_send_status(pudev); + break; + default: + usbd_ctrl_unsupport(pudev); + break; + + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_ctrl_unsupport(pudev); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&pmsc->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + pmsc->alt_setting = setup->wValue; + break; + case USB_STD_REQ_CLEAR_FEATURE: + usbd_ept_close(pudev, (uint8_t)setup->wIndex); + + if((setup->wIndex & 0x80) == 0x80) + { + usbd_flush_tx_fifo(pudev, setup->wIndex & 0x7F); + usbd_ept_open(pudev, (uint8_t)setup->wIndex, EPT_BULK_TYPE, USBD_IN_MAXPACKET_SIZE); + } + else + { + usbd_ept_open(pudev, (uint8_t)setup->wIndex, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + } + bot_scsi_clear_feature(udev, setup->wIndex); + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: usb device core handler type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + UNUSED(recv_len); + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + usbd_flush_tx_fifo(pudev, ept_num&0x7F); + bot_scsi_datain_handler(udev, ept_num); + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + + bot_scsi_dataout_handler(udev, ept_num); + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + UNUSED(udev); + usb_sts_type status = USB_OK; + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + + default: + break; + } + return status; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h new file mode 100644 index 0000000000..80c7c1774c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h @@ -0,0 +1,72 @@ +/** + ************************************************************************** + * @file msc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc class file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_CLASS_H +#define __MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_class + * @{ + */ + +/** @defgroup USB_msc_class_definition + * @{ + */ + +#define USBD_MSC_BULK_IN_EPT 0x81 +#define USBD_MSC_BULK_OUT_EPT 0x01 + +#define USBD_IN_MAXPACKET_SIZE 0x40 +#define USBD_OUT_MAXPACKET_SIZE 0x40 + + +extern usbd_class_handler msc_class_handler; +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c new file mode 100644 index 0000000000..414ee43009 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c @@ -0,0 +1,404 @@ +/** + ************************************************************************** + * @file msc_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "stdio.h" +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "msc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_desc + * @brief usb device msc descriptor + * @{ + */ + +/** @defgroup USB_msc_desc_private_functions + * @{ + */ + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief device descriptor handler structure + */ +usbd_desc_handler msc_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x00, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_MSC_VENDOR_ID), /* idVendor */ + HBYTE(USBD_MSC_VENDOR_ID), /* idVendor */ + LBYTE(USBD_MSC_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_MSC_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_MSC_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_MSC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_MSC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x01, /* bNumInterfaces: 2 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x04, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_MSC, /* bInterfaceClass: msc class code */ + 0x06, /* bInterfaceSubClass: subclass code scsi */ + 0x50, /* bInterfaceProtocol: protocol code BBB */ + 0x05, /* iInterface: index of string descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_MSC_BULK_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_IN_MAXPACKET_SIZE), + HBYTE(USBD_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_MSC_BULK_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_OUT_MAXPACKET_SIZE), + HBYTE(USBD_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_MSC_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_MSC_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_MSC_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_MSC_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_MSC_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_MSC_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_MSC_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = (uint8_t)str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h new file mode 100644 index 0000000000..72edbcdc45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h @@ -0,0 +1,85 @@ +/** + ************************************************************************** + * @file msc_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_DESC_H +#define __MSC_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "msc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_desc + * @{ + */ + +/** @defgroup USB_msc_desc_definition + * @{ + */ + +#define MSC_BCD_NUM 0x0110 + +#define USBD_MSC_VENDOR_ID 0x2E3C +#define USBD_MSC_PRODUCT_ID 0x5720 + +#define USBD_MSC_CONFIG_DESC_SIZE 32 +#define USBD_MSC_SIZ_STRING_LANGID 4 +#define USBD_MSC_SIZ_STRING_SERIAL 0x1A + +#define USBD_MSC_DESC_MANUFACTURER_STRING "Artery" +#define USBD_MSC_DESC_PRODUCT_STRING "AT32 Mass Storage" +#define USBD_MSC_DESC_CONFIGURATION_STRING "Mass Storage Config" +#define USBD_MSC_DESC_INTERFACE_STRING "Mass Storage Interface" + +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) + +extern usbd_desc_handler msc_desc_handler; + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c new file mode 100644 index 0000000000..b8a37bd2aa --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c @@ -0,0 +1,532 @@ +/** + ************************************************************************** + * @file usbh_cdc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_cdc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" +#include "string.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup usbh_cdc_class + * @brief usb host class cdc demo + * @{ + */ + +/** @defgroup usbh_cdc_class_private_functions + * @{ + */ + +static usb_sts_type uhost_init_handler(void *uhost); +static usb_sts_type uhost_reset_handler(void *uhost); +static usb_sts_type uhost_request_handler(void *uhost); +static usb_sts_type uhost_process_handler(void *uhost); +static usb_sts_type get_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding); +static usb_sts_type set_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding); + +static void cdc_process_transmission(usbh_core_type *uhost); +static void cdc_process_reception(usbh_core_type *uhost); +usbh_cdc_type usbh_cdc; + +usbh_class_handler_type uhost_cdc_class_handler = +{ + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_cdc +}; + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t if_x; + usbh_cdc_type *pcdc = &usbh_cdc; + puhost->class_handler->pdata = &usbh_cdc; + + memset((void *)pcdc, 0, sizeof(usbh_cdc_type)); + if_x = usbh_find_interface(puhost, USB_CLASS_CODE_CDC, ABSTRACT_CONTROL_MODEL, COMMON_AT_COMMAND); + if(if_x == 0xFF) + { + USBH_DEBUG("cannot find the interface for communication interface class!"); + return USB_NOT_SUPPORT; + } + else + { + if(if_x < puhost->dev.cfg_desc.cfg.bNumInterfaces) + { + USBH_DEBUG ("switching to interface (#%d)", if_x); + USBH_DEBUG ("class : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceClass); + USBH_DEBUG ("subclass : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceSubClass ); + USBH_DEBUG ("protocol : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceProtocol ); + if(puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceClass == COMMUNICATION_INTERFACE_CLASS_CODE) + { + USBH_DEBUG("CDC device!"); + } + } + else + { + USBH_DEBUG ("cannot select this interface."); + } + + /* collect the notification endpoint address and length */ + if(puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress & 0x80) + { + pcdc->common_interface.notif_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->common_interface.notif_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + /* allocate the length for host channel number in */ + pcdc->common_interface.notif_channel = usbh_alloc_channel(puhost, pcdc->common_interface.notif_endpoint); + + /* enable channel */ + usbh_hc_open(puhost, + pcdc->common_interface.notif_channel, + pcdc->common_interface.notif_endpoint, + puhost->dev.address, + EPT_INT_TYPE, + pcdc->common_interface.notif_endpoint_size, + puhost->dev.speed); + + usbh_set_toggle(puhost, pcdc->common_interface.notif_channel, 0); + + + if_x = usbh_find_interface(puhost, DATA_INTERFACE_CLASS_CODE, RESERVED, NO_CLASS_SPECIFIC_PROTOCOL_CODE); + if(if_x == 0xFF) + { + USBH_DEBUG("cannot find the interface for data interface class!"); + return USB_NOT_SUPPORT; + } + else + { + /* collect the class specific endpoint address and length */ + if(puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress & 0x80) + { + pcdc->data_interface.in_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->data_interface.in_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + else + { + pcdc->data_interface.out_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->data_interface.out_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + + if(puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress & 0x80) + { + pcdc->data_interface.in_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress; + pcdc->data_interface.in_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[1].wMaxPacketSize; + } + else + { + pcdc->data_interface.out_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress; + pcdc->data_interface.out_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[1].wMaxPacketSize; + } + + /* allocate the length for host channel number in */ + pcdc->data_interface.in_channel = usbh_alloc_channel(puhost, pcdc->data_interface.in_endpoint); + /* allocate the length for host channel number out */ + pcdc->data_interface.out_channel = usbh_alloc_channel(puhost, pcdc->data_interface.out_endpoint); + + /* enable in channel */ + usbh_hc_open(puhost, + pcdc->data_interface.in_channel, + pcdc->data_interface.in_endpoint, + puhost->dev.address, + EPT_BULK_TYPE, + pcdc->data_interface.in_endpoint_size, + puhost->dev.speed); + + /* enable out channel */ + usbh_hc_open(puhost, + pcdc->data_interface.out_channel, + pcdc->data_interface.out_endpoint, + puhost->dev.address, + EPT_BULK_TYPE, + pcdc->data_interface.out_endpoint_size, + puhost->dev.speed); + + usbh_set_toggle(puhost, pcdc->data_interface.in_channel, 0); + usbh_set_toggle(puhost, pcdc->data_interface.out_channel, 0); + + pcdc->state = CDC_IDLE_STATE; + + } + } + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + if(pcdc->common_interface.notif_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->common_interface.notif_channel); + usbh_ch_disable(puhost, pcdc->common_interface.notif_channel); + pcdc->common_interface.notif_channel = 0; + } + + if(pcdc->data_interface.in_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->data_interface.in_channel); + usbh_ch_disable(puhost, pcdc->data_interface.in_channel); + pcdc->data_interface.in_channel = 0; + } + + if(pcdc->data_interface.out_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->data_interface.out_channel); + usbh_ch_disable(puhost, pcdc->data_interface.out_channel); + pcdc->data_interface.out_channel = 0; + } + + return status; +} + +/** + * @brief usb host cdc class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + + status = get_linecoding(uhost, &pcdc->linecoding); + + return status; +} + +/** + * @brief usb host cdc get linecoding handler + * @param uhost: to the structure of usbh_core_type + * @param linecoding: pointer to the structure of cdc_line_coding_type + * @retval status: usb_sts_type status + */ +static usb_sts_type get_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + uhost->ctrl.setup.bmRequestType = USB_DIR_D2H | USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE; + uhost->ctrl.setup.bRequest = CDC_GET_LINE_CODING; + uhost->ctrl.setup.wValue = 0; + uhost->ctrl.setup.wLength = LINE_CODING_STRUCTURE_SIZE; + uhost->ctrl.setup.wIndex = 0; + + usbh_ctrl_request(uhost, linecoding->array, LINE_CODING_STRUCTURE_SIZE); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + + return status; +} + +/** + * @brief usb host cdc set linecoding handler + * @param uhost: to the structure of usbh_core_type + * @param linecoding: pointer to the structure of cdc_line_coding_type + * @retval status: usb_sts_type status + */ +static usb_sts_type set_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + + if(puhost->ctrl.state == CONTROL_IDLE ) + { + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE; + uhost->ctrl.setup.bRequest = CDC_SET_LINE_CODING; + uhost->ctrl.setup.wValue = 0; + uhost->ctrl.setup.wLength = LINE_CODING_STRUCTURE_SIZE; + uhost->ctrl.setup.wIndex = 0; + + status = usbh_ctrl_request(uhost, linecoding->array, LINE_CODING_STRUCTURE_SIZE); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + + return status; +} + +/** + * @brief usb host class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status; + + switch(pcdc->state) + { + case CDC_IDLE_STATE: + status = USB_OK; + break; + + case CDC_SET_LINE_CODING_STATE: + status = set_linecoding(puhost, pcdc->puserlinecoding); + if(status == USB_OK) + pcdc->state = CDC_GET_LAST_LINE_CODING_STATE; + break; + + case CDC_GET_LAST_LINE_CODING_STATE: + status = get_linecoding(puhost, &(pcdc->linecoding)); + if(status == USB_OK) + { + pcdc->state = CDC_IDLE_STATE; + if((pcdc->linecoding.line_coding_b.char_format == pcdc->puserlinecoding->line_coding_b.char_format)&& + (pcdc->linecoding.line_coding_b.data_bits == pcdc->puserlinecoding->line_coding_b.data_bits)&& + (pcdc->linecoding.line_coding_b.parity_type == pcdc->puserlinecoding->line_coding_b.parity_type)&& + (pcdc->linecoding.line_coding_b.data_baudrate == pcdc->puserlinecoding->line_coding_b.data_baudrate)) + { + /* line coding changed */ + } + } + pcdc->state = CDC_IDLE_STATE; + break; + + case CDC_TRANSFER_DATA: + cdc_process_transmission(puhost); + cdc_process_reception(puhost); + break; + + case CDC_ERROR_STATE: + status = usbh_clear_ept_feature(puhost, 0, pcdc->common_interface.notif_channel); + if(status == USB_OK) + pcdc->state = CDC_IDLE_STATE; + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host cdc class process transmission handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static void cdc_process_transmission(usbh_core_type *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + + switch(pcdc->data_tx_state) + { + case CDC_SEND_DATA: + if(pcdc->tx_len > pcdc->data_interface.out_endpoint_size) + { + usbh_bulk_send(puhost, pcdc->data_interface.out_channel, (uint8_t*)pcdc->tx_data, pcdc->data_interface.out_endpoint_size); + } + else + { + usbh_bulk_send(puhost, pcdc->data_interface.out_channel, (uint8_t*)pcdc->tx_data, pcdc->tx_len); + } + pcdc->data_tx_state = CDC_SEND_DATA_WAIT; + break; + + case CDC_SEND_DATA_WAIT: + if(uhost->urb_state[pcdc->data_interface.out_channel] == URB_DONE) + { + if(pcdc->tx_len > pcdc->data_interface.out_endpoint_size) + { + pcdc->tx_len -= pcdc->data_interface.out_endpoint_size; + pcdc->tx_data += pcdc->data_interface.out_endpoint_size; + pcdc->data_tx_state = CDC_SEND_DATA; + } + else + { + pcdc->tx_len = 0; + pcdc->data_tx_state = CDC_IDLE; + cdc_transmit_complete(uhost); + } + } + else if( uhost->urb_state[pcdc->data_interface.out_channel] == URB_NOTREADY) + { + pcdc->data_tx_state = CDC_SEND_DATA; + } + break; + + default: + break; + } +} + +/** + * @brief usb host cdc class start transmission handler + * @param uhost: to the structure of usbh_core_type + * @param data: tx data pointer + * @param len: tx data len + * @retval status: usb_sts_type status + */ +void cdc_start_transmission(usbh_core_type *uhost, uint8_t *data, uint32_t len) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + if(pcdc->data_tx_state == CDC_IDLE) + { + pcdc->data_tx_state = CDC_SEND_DATA; + pcdc->state = CDC_TRANSFER_DATA; + pcdc->tx_data = data; + pcdc->tx_len = len; + } +} + + +/** + * @brief usb host cdc class transmit complete + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +__weak void cdc_transmit_complete(usbh_core_type *uhost) +{ + +} + +/** + * @brief usb host cdc class process reception handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static void cdc_process_reception(usbh_core_type *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + uint32_t len = 0; + + switch(pcdc->data_rx_state) + { + case CDC_RECEIVE_DATA: + usbh_bulk_recv(puhost, pcdc->data_interface.in_channel, (uint8_t*)pcdc->rx_data, pcdc->data_interface.in_endpoint_size); + pcdc->data_rx_state = CDC_RECEIVE_DATA_WAIT; + break; + + case CDC_RECEIVE_DATA_WAIT: + if(uhost->urb_state[pcdc->data_interface.in_channel] == URB_DONE) + { + len = uhost->hch[pcdc->data_interface.in_channel].trans_count; + if(pcdc->rx_len > len && len > pcdc->data_interface.in_endpoint_size) + { + pcdc->rx_len -= len; + pcdc->rx_data += len; + pcdc->data_rx_state = CDC_RECEIVE_DATA; + } + else + { + pcdc->data_rx_state = CDC_IDLE; + cdc_receive_complete(uhost); + + } + } + + break; + + default: + break; + } +} + +/** + * @brief usb host cdc class start reception handler + * @param uhost: to the structure of usbh_core_type + * @param data: receive data pointer + * @param len: receive data len + * @retval status: usb_sts_type status + */ +void cdc_start_reception(usbh_core_type *uhost, uint8_t *data, uint32_t len) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + + if(pcdc->data_rx_state == CDC_IDLE) + { + pcdc->data_rx_state = CDC_RECEIVE_DATA; + pcdc->state = CDC_TRANSFER_DATA; + pcdc->rx_data = data; + pcdc->rx_len = len; + } +} + +/** + * @brief usb host cdc class reception complete + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +__weak void cdc_receive_complete(usbh_core_type *uhost) +{ + +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h new file mode 100644 index 0000000000..f5eb101fed --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h @@ -0,0 +1,284 @@ +/** + ************************************************************************** + * @file usbh_cdc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host cdc class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_CLASS_H +#define __USBH_MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_cdc_class + * @{ + */ + +/** @defgroup USBH_cdc_class_definition + * @{ + */ + +/*Communication Class codes*/ +#define USB_CDC_CLASS 0x02 +#define COMMUNICATION_INTERFACE_CLASS_CODE 0x02 + +/*Data Interface Class Codes*/ +#define DATA_INTERFACE_CLASS_CODE 0x0A + +/*Communication sub class codes*/ +#define RESERVED 0x00 +#define DIRECT_LINE_CONTROL_MODEL 0x01 +#define ABSTRACT_CONTROL_MODEL 0x02 +#define TELEPHONE_CONTROL_MODEL 0x03 +#define MULTICHANNEL_CONTROL_MODEL 0x04 +#define CAPI_CONTROL_MODEL 0x05 +#define ETHERNET_NETWORKING_CONTROL_MODEL 0x06 +#define ATM_NETWORKING_CONTROL_MODEL 0x07 + + +/*Communication Interface Class Control Protocol Codes*/ +#define NO_CLASS_SPECIFIC_PROTOCOL_CODE 0x00 +#define COMMON_AT_COMMAND 0x01 +#define VENDOR_SPECIFIC 0xFF + + +#define CS_INTERFACE 0x24 +#define CDC_PAGE_SIZE_64 0x40 + +/*Class-Specific Request Codes*/ +#define CDC_SEND_ENCAPSULATED_COMMAND 0x00 +#define CDC_GET_ENCAPSULATED_RESPONSE 0x01 +#define CDC_SET_COMM_FEATURE 0x02 +#define CDC_GET_COMM_FEATURE 0x03 +#define CDC_CLEAR_COMM_FEATURE 0x04 + +#define CDC_SET_AUX_LINE_STATE 0x10 +#define CDC_SET_HOOK_STATE 0x11 +#define CDC_PULSE_SETUP 0x12 +#define CDC_SEND_PULSE 0x13 +#define CDC_SET_PULSE_TIME 0x14 +#define CDC_RING_AUX_JACK 0x15 + +#define CDC_SET_LINE_CODING 0x20 +#define CDC_GET_LINE_CODING 0x21 +#define CDC_SET_CONTROL_LINE_STATE 0x22 +#define CDC_SEND_BREAK 0x23 + +#define CDC_SET_RINGER_PARMS 0x30 +#define CDC_GET_RINGER_PARMS 0x31 +#define CDC_SET_OPERATION_PARMS 0x32 +#define CDC_GET_OPERATION_PARMS 0x33 +#define CDC_SET_LINE_PARMS 0x34 +#define CDC_GET_LINE_PARMS 0x35 +#define CDC_DIAL_DIGITS 0x36 +#define CDC_SET_UNIT_PARAMETER 0x37 +#define CDC_GET_UNIT_PARAMETER 0x38 +#define CDC_CLEAR_UNIT_PARAMETER 0x39 +#define CDC_GET_PROFILE 0x3A + +#define CDC_SET_ETHERNET_MULTICAST_FILTERS 0x40 +#define CDC_SET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x41 +#define CDC_GET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x42 +#define CDC_SET_ETHERNET_PACKET_FILTER 0x43 +#define CDC_GET_ETHERNET_STATISTIC 0x44 + +#define CDC_SET_ATM_DATA_FORMAT 0x50 +#define CDC_GET_ATM_DEVICE_STATISTICS 0x51 +#define CDC_SET_ATM_DEFAULT_VC 0x52 +#define CDC_GET_ATM_VC_STATISTICS 0x53 + + +/* wValue for SetControlLineState*/ +#define CDC_ACTIVATE_CARRIER_SIGNAL_RTS 0x0002 +#define CDC_DEACTIVATE_CARRIER_SIGNAL_RTS 0x0000 +#define CDC_ACTIVATE_SIGNAL_DTR 0x0001 +#define CDC_DEACTIVATE_SIGNAL_DTR 0x0000 + +#define LINE_CODING_STRUCTURE_SIZE 0x07 + +/* states for cdc state machine */ +typedef enum +{ + CDC_IDLE = 0x0, + CDC_SEND_DATA = 0x1, + CDC_SEND_DATA_WAIT = 0x2, + CDC_RECEIVE_DATA = 0x3, + CDC_RECEIVE_DATA_WAIT = 0x4, +} cdc_data_state_type; + +typedef enum +{ + CDC_IDLE_STATE = 0x0, + CDC_SET_LINE_CODING_STATE = 0x1, + CDC_GET_LAST_LINE_CODING_STATE = 0x2, + CDC_TRANSFER_DATA = 0x3, + CDC_ERROR_STATE = 0x4, +} cdc_state_type; + + +/*line coding structure*/ +typedef union _cdc_line_coding_structure +{ + uint8_t array[LINE_CODING_STRUCTURE_SIZE]; + + struct + { + uint32_t data_baudrate; /*data terminal rate, in bits per second*/ + uint8_t char_format; /* Stop bits + 0 - 1 Stop bit + 1 - 1.5 Stop bits + 2 - 2 Stop bits*/ + uint8_t parity_type; /* parity + 0 - none + 1 - odd + 2 - even + 3 - mark + 4 - space*/ + uint8_t data_bits; /* data bits (5, 6, 7, 8 or 16). */ + }line_coding_b; +} cdc_line_coding_type; + + + +/* header functional descriptor */ +typedef struct _functional_descriptor_header +{ + uint8_t bfunctionlength; /* size of this descriptor. */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* header functional descriptor subtype as */ + uint16_t bcdcdc; /* usb class definitions for communication + devices specification release number in + binary-coded decimal. */ +} cdc_headerfuncdesc_type; + +/* call management functional descriptor */ +typedef struct _callmgmt_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* call management functional descriptor subtype */ + uint8_t bmcapabilities; /* bmcapabilities: d0+d1 */ + uint8_t bdatainterface; /* bdatainterface: 1 */ +} cdc_callmgmtfuncdesc_type; + +/* abstract control management functional descriptor */ +typedef struct _abstractcntrlmgmt_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* abstract control management functional + descriptor subtype */ + uint8_t bmcapabilities; /* the capabilities that this configuration supports */ +} cdc_abstcntrlmgmtfuncdesc_type; + +/* union functional descriptor */ +typedef struct _union_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* union functional descriptor subtype */ + uint8_t bmasterinterface; /* the interface number of the communication or + data class interface */ + uint8_t bslaveinterface0; /* interface number of first slave */ +} cdc_unionfuncdesc_type; + + +typedef struct _usbh_cdcinterfacedesc +{ + cdc_headerfuncdesc_type cdc_headerfuncdesc; + cdc_callmgmtfuncdesc_type cdc_callmgmtfuncdesc; + cdc_abstcntrlmgmtfuncdesc_type cdc_abstcntrlmgmtfuncdesc; + cdc_unionfuncdesc_type cdc_unionfuncdesc; +} cdc_interfacedesc_type; + + +/* structure for cdc process */ +typedef struct +{ + uint8_t notif_channel; + uint8_t notif_endpoint; + uint8_t buff[8]; + uint16_t notif_endpoint_size; +} cdc_common_interface_type; + +typedef struct +{ + uint8_t in_channel; + uint8_t out_channel; + uint8_t out_endpoint; + uint8_t in_endpoint; + uint8_t buff[8]; + uint16_t out_endpoint_size; + uint16_t in_endpoint_size; +} cdc_data_interface_type; + +/** + * @brief usb cdc struct + */ +typedef struct +{ + cdc_common_interface_type common_interface; + cdc_data_interface_type data_interface; + cdc_interfacedesc_type cdc_desc; + cdc_line_coding_type linecoding; + cdc_line_coding_type *puserlinecoding; + cdc_state_type state; + cdc_data_state_type data_tx_state; + cdc_data_state_type data_rx_state; + + uint8_t *rx_data; + uint8_t *tx_data; + uint32_t rx_len; + uint32_t tx_len; +}usbh_cdc_type; + +extern usbh_class_handler_type uhost_cdc_class_handler; +extern usbh_cdc_type usbh_cdc; +void cdc_start_transmission(usbh_core_type *phost, uint8_t *data, uint32_t len); +void cdc_start_reception(usbh_core_type *uhost, uint8_t *data, uint32_t len); +__weak void cdc_transmit_complete(usbh_core_type *uhost); +__weak void cdc_receive_complete(usbh_core_type *uhost); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c new file mode 100644 index 0000000000..7bc618e90f --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c @@ -0,0 +1,453 @@ +/** + ************************************************************************** + * @file usbh_hid_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + #include "usbh_hid_class.h" + #include "usb_conf.h" + #include "usbh_core.h" + #include "usbh_ctrl.h" + #include "usbh_hid_mouse.h" + #include "usbh_hid_keyboard.h" + + /** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class + * @brief usb host class hid demo + * @{ + */ + +/** @defgroup USBH_hid_class_private_functions + * @{ + */ + + static usb_sts_type uhost_init_handler(void *uhost); + static usb_sts_type uhost_reset_handler(void *uhost); + static usb_sts_type uhost_request_handler(void *uhost); + static usb_sts_type uhost_process_handler(void *uhost); + + usbh_hid_type usbh_hid; + usbh_class_handler_type uhost_hid_class_handler = + { + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_hid + }; + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t hidx, eptidx = 0; + usbh_hid_type *phid = &usbh_hid; + + puhost->class_handler->pdata = &usbh_hid; + + /* get hid interface */ + hidx = usbh_find_interface(puhost, USB_CLASS_CODE_HID, 0x01, 0xFF); + if(hidx == 0xFF) + { + USBH_DEBUG("Unsupport Device!"); + return USB_NOT_SUPPORT; + } + + /* get hid protocol */ + phid->protocol = puhost->dev.cfg_desc.interface[hidx].interface.bInterfaceProtocol; + + if(phid->protocol == USB_HID_MOUSE_PROTOCOL_CODE) + { + USBH_DEBUG("Mouse Device!"); + } + else if(phid->protocol == USB_HID_KEYBOARD_PROTOCOL_CODE) + { + USBH_DEBUG("Keyboard Device!"); + } + + for(eptidx = 0; eptidx < puhost->dev.cfg_desc.interface[hidx].interface.bNumEndpoints; eptidx ++) + { + if(puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress & 0x80) + { + /* find interface out endpoint information */ + phid->eptin = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress; + phid->in_maxpacket = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].wMaxPacketSize; + phid->in_poll = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bInterval; + + phid->chin = usbh_alloc_channel(puhost, phid->eptin); + /* enable channel */ + usbh_hc_open(puhost, phid->chin,phid->eptin, + puhost->dev.address, EPT_INT_TYPE, + phid->in_maxpacket, + puhost->dev.speed); + usbh_set_toggle(puhost, phid->chin, 0); + } + else + { + /* get interface out endpoint information */ + phid->eptout = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress; + phid->out_maxpacket = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].wMaxPacketSize; + phid->out_poll = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bInterval; + + phid->chout = usbh_alloc_channel(puhost, usbh_hid.eptout); + /* enable channel */ + usbh_hc_open(puhost, phid->chout, phid->eptout, + puhost->dev.address, EPT_INT_TYPE, + phid->out_maxpacket, + puhost->dev.speed); + usbh_set_toggle(puhost, phid->chout, 0); + } + } + phid->ctrl_state = USB_HID_STATE_IDLE; + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + if(phid->chin != 0) + { + /* free in channel */ + usbh_free_channel(puhost, phid->chin); + usbh_ch_disable(puhost, phid->chin); + phid->chin = 0; + } + + if(phid->chout != 0) + { + /* free out channel */ + usbh_free_channel(puhost, phid->chout); + usbh_ch_disable(puhost, phid->chout); + phid->chout = 0; + } + + return status; +} + +/** + * @brief usb host hid class get descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: descriptor length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_get_desc(void *uhost, uint16_t length) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + if(puhost->ctrl.state == CONTROL_IDLE) + { + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + wvalue = (0x21 << 8) & 0xFF00; + + usbh_get_descriptor(puhost, length, bm_req, + wvalue, puhost->rx_buffer); + } + else + { + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + phid->hid_desc.bLength = puhost->rx_buffer[0]; + phid->hid_desc.bDescriptorType = puhost->rx_buffer[1]; + phid->hid_desc.bcdHID = SWAPBYTE(puhost->rx_buffer+2); + phid->hid_desc.bCountryCode = puhost->rx_buffer[4]; + phid->hid_desc.bNumDescriptors = puhost->rx_buffer[5]; + phid->hid_desc.bReportDescriptorType = puhost->rx_buffer[6]; + phid->hid_desc.wItemLength = SWAPBYTE(puhost->rx_buffer+7); + status = USB_OK; + } + } + return status; +} + + +/** + * @brief usb host hid class get report + * @param uhost: to the structure of usbh_core_type + * @param length: reprot length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_get_report(void *uhost, uint16_t length) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + if(puhost->ctrl.state == CONTROL_IDLE) + { + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + wvalue = (0x22 << 8) & 0xFF00; + + usbh_get_descriptor(puhost, length, bm_req, + wvalue, puhost->rx_buffer); + } + else + { + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host hid class set idle + * @param uhost: to the structure of usbh_core_type + * @param id: id + * @param dr: dr + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_set_idle(void *uhost, uint8_t id, uint8_t dr) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = USB_HID_SET_IDLE; + puhost->ctrl.setup.wValue = (dr << 8) | id; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host hid class set protocol + * @param uhost: to the structure of usbh_core_type + * @param protocol: portocol number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_set_protocol(void *uhost, uint8_t protocol) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = USB_HID_SET_PROTOCOL; + puhost->ctrl.setup.wValue = protocol; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host clear feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_endpoint_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num) +{ + usb_sts_type status = USB_WAIT; + usbh_core_type *puhost = (usbh_core_type *)uhost; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + puhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + puhost->ctrl.setup.wValue = 0x00; + puhost->ctrl.setup.wLength = 0; + puhost->ctrl.setup.wIndex = ept_num; + if((ept_num & 0x80) == USB_DIR_D2H) + { + puhost->hch[hc_num].toggle_in = 0; + } + else + { + puhost->hch[hc_num].toggle_out = 0; + } + status = usbh_ctrl_request(puhost, 0, 0); + } + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + return status; +} + +/** + * @brief usb host hid class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usb_sts_type status = USB_WAIT; + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + + switch(phid->ctrl_state) + { + case USB_HID_STATE_IDLE: + phid->ctrl_state = USB_HID_STATE_GET_DESC; + break; + case USB_HID_STATE_GET_DESC: + if(usbh_hid_get_desc(puhost, 9) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_GET_REPORT; + } + break; + case USB_HID_STATE_GET_REPORT: + if(usbh_hid_get_report(puhost, phid->hid_desc.wItemLength) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_SET_IDLE; + } + break; + case USB_HID_STATE_SET_IDLE: + if(usbh_hid_set_idle(puhost, 0, 0) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_SET_PROTOCOL; + } + break; + case USB_HID_STATE_SET_PROTOCOL: + if(usbh_hid_set_protocol(puhost, 0) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_COMPLETE; + } + break; + case USB_HID_STATE_COMPLETE: + phid->state = USB_HID_INIT; + status = USB_OK; + break; + default: + break; + } + + return status; +} + +/** + * @brief usb host hid class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + urb_sts_type urb_status; + switch(phid->state) + { + case USB_HID_INIT: + phid->state = USB_HID_GET; + break; + + case USB_HID_GET: + usbh_interrupt_recv(puhost, phid->chin, (uint8_t *)phid->buffer, phid->in_maxpacket); + phid->state = USB_HID_POLL; + phid->poll_timer = usbh_get_frame(puhost->usb_reg); + break; + + case USB_HID_POLL: + if((usbh_get_frame(puhost->usb_reg) - phid->poll_timer) >= phid->in_poll ) + { + phid->state = USB_HID_GET; + } + else + { + urb_status = usbh_get_urb_status(puhost, phid->chin); + if(urb_status == URB_DONE) + { + puhost->urb_state[phid->chin] = URB_IDLE; + if(phid->protocol == USB_HID_MOUSE_PROTOCOL_CODE) + { + usbh_hid_mouse_decode((uint8_t *)phid->buffer); + } + else if(phid->protocol == USB_HID_KEYBOARD_PROTOCOL_CODE) + { + usbh_hid_keyboard_decode((uint8_t *)phid->buffer); + } + + } + else if(urb_status == URB_STALL) + { + if(usbh_clear_endpoint_feature(puhost, phid->eptin, phid->chin) == USB_OK) + { + phid->state = USB_HID_GET; + } + } + } + break; + + default: + break; + } + return USB_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h new file mode 100644 index 0000000000..311b821812 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h @@ -0,0 +1,148 @@ +/** + ************************************************************************** + * @file usbh_hid_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_CLASS_H +#define __USBH_HID_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class + * @{ + */ + +/** @defgroup USBH_hid_class_definition + * @{ + */ + +/** + * @brief usb hid protocol code + */ +#define USB_HID_NONE_PROTOCOL_CODE 0x00 +#define USB_HID_KEYBOARD_PROTOCOL_CODE 0x01 +#define USB_HID_MOUSE_PROTOCOL_CODE 0x02 + +/** + * @brief usb hid request code + */ +#define USB_HID_GET_REPORT 0x01 +#define USB_HID_GET_IDLE 0x02 +#define USB_HID_GET_PROTOCOL 0x03 +#define USB_HID_SET_REPORT 0x09 +#define USB_HID_SET_IDLE 0x0A +#define USB_HID_SET_PROTOCOL 0x0B + +/** + * @brief usb hid request state + */ +typedef enum +{ + USB_HID_STATE_IDLE, + USB_HID_STATE_GET_DESC, + USB_HID_STATE_GET_REPORT, + USB_HID_STATE_SET_IDLE, + USB_HID_STATE_SET_PROTOCOL, + USB_HID_STATE_COMPLETE, +}usb_hid_ctrl_state_type; + +/** + * @brief usb hid process state + */ +typedef enum +{ + USB_HID_INIT, + USB_HID_GET, + USB_HID_SEND, + USB_HID_POLL, + USB_HID_BUSY, + USB_HID_ERROR, +}usb_hid_state_type; + +/** + * @brief usb hid descriptor type + */ +typedef struct +{ + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t bcdHID; + uint8_t bCountryCode; + uint8_t bNumDescriptors; + uint8_t bReportDescriptorType; + uint16_t wItemLength; +}usb_hid_desc_type; + +/** + * @brief usb hid struct + */ +typedef struct +{ + uint8_t chin; + uint8_t eptin; + uint16_t in_maxpacket; + uint8_t in_poll; + + uint8_t chout; + uint8_t eptout; + uint16_t out_maxpacket; + uint8_t out_poll; + uint8_t protocol; + + + usb_hid_desc_type hid_desc; + usb_hid_ctrl_state_type ctrl_state; + usb_hid_state_type state; + uint16_t poll_timer; + uint32_t buffer[16]; +}usbh_hid_type; + +extern usbh_class_handler_type uhost_hid_class_handler; + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c new file mode 100644 index 0000000000..3c124306f8 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c @@ -0,0 +1,255 @@ +/** + ************************************************************************** + * @file usbh_hid_keyboard.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid keyboard type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + #include "usbh_hid_keyboard.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard + * @brief usb host class hid keyboard + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard_private_functions + * @{ + */ + +static const uint8_t hid_keyboard_codes[] = +{ + 0, 0, 0, 0, 31, 50, 48, 33, + 19, 34, 35, 36, 24, 37, 38, 39, + 52, 51, 25, 26, 17, 20, 32, 21, + 23, 49, 18, 47, 22, 46, 2, 3, + 4, 5, 6, 7, 8, 9, 10, 11, + 43, 110, 15, 16, 61, 12, 13, 27, + 28, 29, 42, 40, 41, 1, 53, 54, + 55, 30, 112, 113, 114, 115, 116, 117, + 118, 119, 120, 121, 122, 123, 124, 125, + 126, 75, 80, 85, 76, 81, 86, 89, + 79, 84, 83, 90, 95, 100, 105, 106, + 108, 93, 98, 103, 92, 97, 102, 91, + 96, 101, 99, 104, 45, 129, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 107, 0, 56, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 58, 44, 60, 127, 64, 57, 62, 128, +}; + +#ifdef QWERTY_KEYBOARD + +static const int8_t hid_keyboard_key[] = { + '\0', '`', '1', '2', '3', '4', '5', '6', + '7', '8', '9', '0', '-', '=', '\0', '\r', + '\t', 'q', 'w', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', + '\0', 'a', 's', 'd', 'f', 'g', 'h', 'j', + 'k', 'l', ';', '\'', '\0', '\n', + '\0', '\0', 'z', 'x', 'c', 'v', 'b', 'n', + 'm', ',', '.', '/', '\0', '\0', + '\0', '\0', '\0', ' ', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '7', '4', '1', + '\0', '/', '8', '5', '2', + '0', '*', '9', '6', '3', + '.', '-', '+', '\0', '\n', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0' +}; + +static const int8_t hid_keyboard_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', + '_', '+', '\0', '\0', '\0', 'Q', 'W', 'E', 'R', 'T', 'Y', 'U', + 'I', 'O', 'P', '{', '}', '|', '\0', 'A', 'S', 'D', 'F', 'G', + 'H', 'J', 'K', 'L', ':', '"', '\0', '\n', '\0', '\0', 'Z', 'X', + 'C', 'V', 'B', 'N', 'M', '<', '>', '?', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +#else +static const int8_t hid_keyboard_key[] = { + '\0', '`', '1', '2', '3', '4', '5', '6', '7', '8', '9', '0', + '-', '=', '\0', '\r', '\t', 'a', 'z', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', '\0', 'q', 's', 'd', 'f', 'g', + 'h', 'j', 'k', 'l', 'm', '\0', '\0', '\n', '\0', '\0', 'w', 'x', + 'c', 'v', 'b', 'n', ',', ';', ':', '!', '\0', '\0', '\0', '\0', + '\0', ' ', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '7', '4', '1','\0', '/', + '8', '5', '2', '0', '*', '9', '6', '3', '.', '-', '+', '\0', + '\n', '\0', '\0', '\0', '\0', '\0', '\0','\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +static const int8_t hid_keyboard_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', '_', + '+', '\0', '\0', '\0', 'A', 'Z', 'E', 'R', 'T', 'Y', 'U', 'I', 'O', + 'P', '{', '}', '*', '\0', 'Q', 'S', 'D', 'F', 'G', 'H', 'J', 'K', + 'L', 'M', '%', '\0', '\n', '\0', '\0', 'W', 'X', 'C', 'V', 'B', 'N', + '?', '.', '/', '\0', '\0', '\0','\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; +#endif + +/** + * @brief usb host hid keyboard decode + * @param data: keyboard data + * @retval none + */ +void usbh_hid_keyboard_decode(uint8_t *data) +{ + static uint8_t shift; + static uint8_t keys[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t keys_n[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t keys_l[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t key_newest; + static uint8_t nb_keys; + static uint8_t nb_keys_n; + static uint8_t nb_keys_l; + + uint8_t idx; + uint8_t idy; + uint8_t err; + uint8_t out; + + nb_keys = 0; + nb_keys_n = 0; + nb_keys_l = 0; + key_newest = 0; + + if(data[0] == KEYBOARD_LEFT_SHIFT || data[0] == KEYBOARD_RIGHT_SHIFT) + { + shift = TRUE; + } + else + { + shift = FALSE; + } + err = FALSE; + + for(idx = 2; idx < 2 + KEYBOARD_MAX_NB_PRESSED; idx ++) + { + if((data[idx] == 0x01) || + (data[idx] == 0x02) || + (data[idx] == 0x03)) + { + err = TRUE; + } + } + + if(err == TRUE) + { + return; + } + + nb_keys = 0; + nb_keys_n = 0; + for(idx = 2; idx < 2 + KEYBOARD_MAX_NB_PRESSED; idx ++) + { + if(data[idx] != 0) + { + keys[nb_keys] = data[idx]; + nb_keys ++; + for(idy = 0; idy < nb_keys_l; idy ++) + { + if(data[idx] == keys_l[idy]) + { + break; + } + } + + if(idy == nb_keys_l) + { + keys_n[nb_keys_n] = data[idx]; + nb_keys_n ++; + } + + } + } + + if(nb_keys_n == 1) + { + key_newest = keys_n[0]; + + if(shift == TRUE) + { + out = hid_keyboard_key_shift[hid_keyboard_codes[key_newest]]; + } + else + { + out = hid_keyboard_key[hid_keyboard_codes[key_newest]]; + } + /* callback user handler */ + USBH_DEBUG("%c", out); + } + else + { + key_newest = 0; + } + + nb_keys_l = nb_keys; + for(idx = 0; idx < KEYBOARD_MAX_NB_PRESSED; idx ++) + { + keys_l[idx] = keys[idx]; + } + return; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h new file mode 100644 index 0000000000..f9aba52aa6 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h @@ -0,0 +1,84 @@ +/** + ************************************************************************** + * @file usbh_hid_keyboard.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid keyboard header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_KEYBOARD_H +#define __USBH_HID_KEYBOARD_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class_keyboard + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard_definition + * @{ + */ + + /** + * @brief usb keyboard option code + */ +#define KEYBOARD_LEFT_CTRL 0x01 +#define KEYBOARD_LEFT_SHIFT 0x02 +#define KEYBOARD_LEFT_ALT 0x04 +#define KEYBOARD_LEFT_GUI 0x08 +#define KEYBOARD_RIGHT_CTRL 0x10 +#define KEYBOARD_RIGHT_SHIFT 0x20 +#define KEYBOARD_RIGHT_ALT 0x40 +#define KEYBOARD_RIGHT_GUI 0x80 + +#define KEYBOARD_MAX_NB_PRESSED 6 + +#ifndef AZERTY_KEYBOARD + #define QWERTY_KEYBOARD +#endif + +void usbh_hid_keyboard_decode(uint8_t *data); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c new file mode 100644 index 0000000000..75228a0902 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c @@ -0,0 +1,188 @@ +/** + ************************************************************************** + * @file usbh_hid_mouse.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid mouse type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_hid_mouse.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class_mouse + * @brief usb host class hid mouse + * @{ + */ + +/** @defgroup USBH_hid_class_mouse_private_functions + * @{ + */ + +usb_hid_mouse_type hid_mouse; +uint16_t x_pos = 0, y_pos = 0; + +/** + * @brief usb host hid position + * @param x: x position + * @param y: y position + * @retval none + */ +void usbh_hid_mouse_position(uint8_t x, uint8_t y) +{ + if((x != 0) || (y != 0)) + { + x_pos += x / 2; + y_pos += y / 2; + + if(x_pos > MOUSE_WINDOW_WIDTH - 12) + { + x_pos = MOUSE_WINDOW_WIDTH - 12; + } + if(y_pos > MOUSE_WINDOW_HEIGHT - 12) + { + y_pos = MOUSE_WINDOW_HEIGHT - 12; + } + + if(x_pos < 2) + { + x_pos = 2; + } + if(y_pos < 2) + { + y_pos = 2; + } + USBH_DEBUG("Moving Mouse"); + } + +} + +/** + * @brief usb host hid button press + * @param button: button id + * @retval none + */ +void usbh_hid_mouse_button_press(uint8_t button) +{ + switch(button) + { + case MOUSE_BUTTON_LEFT: + /* left button */ + USBH_DEBUG("Left Button Pressed "); + break; + case MOUSE_BUTTON_RIGHT: + USBH_DEBUG("Right Button Pressed "); + /* left button */ + break; + case MOUSE_BUTTON_MIDDLE: + USBH_DEBUG("Middle Button Pressed "); + /* middle button */ + break; + } +} + +/** + * @brief usb host hid button release + * @param button: button id + * @retval none + */ +void usbh_hid_mouse_button_release(uint8_t button) +{ + switch(button) + { + case MOUSE_BUTTON_LEFT: + /* left button */ + USBH_DEBUG("Left Button Released "); + break; + case MOUSE_BUTTON_RIGHT: + /* left button */ + USBH_DEBUG("Right Button Released "); + break; + case MOUSE_BUTTON_MIDDLE: + /* middle button */ + USBH_DEBUG("Middle Button Released "); + break; + } +} + +/** + * @brief usb host hid mouse process + * @param mouse: mouse data type + * @retval none + */ +void usbh_hid_mouse_process(usb_hid_mouse_type *mouse) +{ + uint8_t idx = 1; + static uint8_t b_state[3] = {0}; + if((mouse->x != 0) && (mouse->y != 0)) + { + usbh_hid_mouse_position(mouse->x, mouse->y); + } + + for(idx = 0; idx < 3; idx ++) + { + if(mouse->button & 1 << idx) + { + if(b_state[idx] == 0) + { + usbh_hid_mouse_button_press(idx); + b_state[idx] = 1; + } + } + else + { + if(b_state[idx] == 1) + { + usbh_hid_mouse_button_release(idx); + b_state[idx] = 0; + } + } + } +} + +/** + * @brief usb host hid mouse decode + * @param mouse_data: mouse data + * @retval none + */ +void usbh_hid_mouse_decode(uint8_t *mouse_data) +{ + hid_mouse.button = mouse_data[0]; + hid_mouse.x = mouse_data[1]; + hid_mouse.y = mouse_data[2]; + hid_mouse.z = mouse_data[3]; + + usbh_hid_mouse_process(&hid_mouse); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h new file mode 100644 index 0000000000..ac32a1fb29 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h @@ -0,0 +1,93 @@ +/** + ************************************************************************** + * @file usbh_hid_mouse.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid mouse header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_MOUSE_H +#define __USBH_HID_MOUSE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class_mouse + * @{ + */ + +/** @defgroup USBH_hid_class_mouse_definition + * @{ + */ + +/** + * @brief usb hid mouse x y + */ +#define MOUSE_WINDOW_X 100 +#define MOUSE_WINDOW_Y 220 +#define MOUSE_WINDOW_HEIGHT 90 +#define MOUSE_WINDOW_WIDTH 128 + + /** + * @brief usb hid mouse button + */ +#define MOUSE_BUTTON_LEFT 0x00 +#define MOUSE_BUTTON_RIGHT 0x01 +#define MOUSE_BUTTON_MIDDLE 0x02 + +/** + * @brief usb hid mouse type + */ +typedef struct +{ + uint8_t button; + uint8_t x; + uint8_t y; + uint8_t z; +}usb_hid_mouse_type; + +void usbh_hid_mouse_decode(uint8_t *mouse_data); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c new file mode 100644 index 0000000000..928ff25ba4 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c @@ -0,0 +1,671 @@ +/** + ************************************************************************** + * @file usbh_msc_bot_scsi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc bulk-only transfer and scsi type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_msc_bot_scsi.h" +#include "usbh_msc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class + * @brief usb host class msc bot scsi + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class_private_functions + * @{ + */ + +static usb_sts_type usbh_bot_cbw(msc_bot_cbw_type *cbw, uint32_t data_length, uint8_t cmd_len, uint8_t flag); +static usb_sts_type usbh_cmd_inquiry(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_capacity10(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_test_unit_ready(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_requset_sense(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_write(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer); +static usb_sts_type usbh_cmd_read(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer); + +/** + * @brief usb host bulk-only cbw + * @param cbw: to the structure of msc_bot_cbw_type + * @param data_length: data length + * @param cmd_len: command len + * @param flag: cbw flag + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_bot_cbw(msc_bot_cbw_type *cbw, uint32_t data_length, uint8_t cmd_len, uint8_t flag) +{ + uint8_t i_index; + cbw->dCBWSignature = MSC_CBW_SIGNATURE; + cbw->dCBWTag = MSC_CBW_TAG; + cbw->dCBWDataTransferLength = data_length; + cbw->bmCBWFlags = flag; + cbw->bCBWCBLength = cmd_len; + for(i_index = 0; i_index < MSC_CBW_CB_LEN; i_index ++) + { + cbw->CBWCB[i_index] = 0x00; + } + return USB_OK; +} + +/** + * @brief usb host msc command inquiry + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_inquiry(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + cmd[0] = MSC_OPCODE_INQUIRY; + cmd[1] = lun << 5; + cmd[4] = MSC_INQUIRY_DATA_LEN; + + bot_trans->data = (uint8_t *)&msc_struct->l_unit_n[lun].inquiry; + return USB_OK; +} + +/** + * @brief usb host msc command capacity10 + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_capacity10(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + cmd[0] = MSC_OPCODE_CAPACITY; + cmd[1] = lun << 5; + + msc_struct->bot_trans.data = (uint8_t *)bot_trans->buffer; + return USB_OK; +} + +/** + * @brief usb host msc command test unit ready + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_test_unit_ready(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + cmd[0] = MSC_OPCODE_TEST_UNIT_READY; + cmd[1] = lun << 5; + + return USB_OK; +} + +/** + * @brief usb host msc command request sense + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_requset_sense(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + cmd[0] = MSC_OPCODE_REQUEST_SENSE; + cmd[1] = lun << 5; + cmd[4] = MSC_REQUEST_SENSE_DATA_LEN; + + bot_trans->data = bot_trans->buffer; + return USB_OK; +} + +/** + * @brief usb host msc command write + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @param data_len: transfer data length + * @param address: logical block address + * @param buffer: transfer data buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_write(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer) +{ + cmd[0] = MSC_OPCODE_WRITE10; + cmd[1] = lun << 5; + cmd[2] = (uint8_t)(address >> 24); + cmd[3] = (uint8_t)(address >> 16); + cmd[4] = (uint8_t)(address >> 8); + cmd[5] = (uint8_t)(address & 0xFF); + + cmd[7] = data_len >> 8; + cmd[8] = data_len; + + bot_trans->data = buffer; + return USB_OK; +} + +/** + * @brief usb host msc command read + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @param data_len: transfer data length + * @param address: logical block address + * @param buffer: transfer data buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_read(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer) +{ + cmd[0] = MSC_OPCODE_READ10; + cmd[1] = lun << 5; + cmd[2] = (uint8_t)(address >> 24); + cmd[3] = (uint8_t)(address >> 16); + cmd[4] = (uint8_t)(address >> 8); + cmd[5] = (uint8_t)(address & 0xFF); + + cmd[7] = data_len >> 8; + cmd[8] = data_len; + + bot_trans->data = buffer; + return USB_OK; +} + +/** + * @brief usb host csw check + * @param cbw: to the structure of msc_bot_cbw_type + * @param csw: to the structure of msc_bot_csw_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_check_csw(void *uhost, msc_bot_cbw_type *cbw, msc_bot_csw_type *csw) +{ + usb_sts_type status = USB_FAIL; + if(csw->dCBWSignature == MSC_CSW_SIGNATURE) + { + if(csw->dCBWTag == cbw->dCBWTag) + { + if(csw->bCSWStatus == 0) + { + status = USB_OK; + } + } + } + return status; +} + +/** + * @brief usb host msc bulk-only request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @retval status: usb_sts_type status + */ +usb_sts_type usb_bot_request(void *uhost, msc_bot_trans_type *bot_trans) +{ + usb_sts_type status = USB_WAIT; + urb_sts_type urb_status; + usb_sts_type clr_status; + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + switch(bot_trans->bot_state) + { + case BOT_STATE_SEND_CBW: + usbh_bulk_send(puhost, msc_struct->chout, (uint8_t *)(&bot_trans->cbw), MSC_CBW_LEN); + bot_trans->bot_state = BOT_STATE_SEND_CBW_WAIT; + break; + + case BOT_STATE_SEND_CBW_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chout); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength != 0) + { + if(bot_trans->cbw.bmCBWFlags == MSC_CBW_FLAG_IN) + { + bot_trans->bot_state = BOT_STATE_DATA_IN; + } + else + { + bot_trans->bot_state = BOT_STATE_DATA_OUT; + } + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_NOTREADY) + { + bot_trans->bot_state = BOT_STATE_SEND_CBW; + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_OUT; + } + break; + + case BOT_STATE_DATA_IN: + usbh_bulk_recv(puhost, msc_struct->chin, bot_trans->data, + msc_struct->in_maxpacket); + bot_trans->bot_state = BOT_STATE_DATA_IN_WAIT; + break; + + case BOT_STATE_DATA_IN_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chin); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength > msc_struct->in_maxpacket) + { + bot_trans->data += msc_struct->in_maxpacket; + bot_trans->cbw.dCBWDataTransferLength -= msc_struct->in_maxpacket; + } + else + { + bot_trans->cbw.dCBWDataTransferLength = 0; + } + if(bot_trans->cbw.dCBWDataTransferLength > 0) + { + usbh_bulk_recv(puhost, msc_struct->chin, bot_trans->data, + msc_struct->in_maxpacket); + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + + break; + + case BOT_STATE_DATA_OUT: + usbh_bulk_send(puhost, msc_struct->chout, bot_trans->data, msc_struct->out_maxpacket); + bot_trans->bot_state = BOT_STATE_DATA_OUT_WAIT; + break; + + case BOT_STATE_DATA_OUT_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chout); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength > msc_struct->out_maxpacket) + { + bot_trans->data += msc_struct->out_maxpacket; + bot_trans->cbw.dCBWDataTransferLength -= msc_struct->out_maxpacket; + } + else + { + bot_trans->cbw.dCBWDataTransferLength = 0; + } + if(bot_trans->cbw.dCBWDataTransferLength > 0) + { + usbh_bulk_send(puhost, msc_struct->chout, bot_trans->data, msc_struct->out_maxpacket); + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_NOTREADY) + { + bot_trans->bot_state = BOT_STATE_DATA_OUT; + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_OUT; + } + break; + + case BOT_STATE_RECV_CSW: + usbh_bulk_recv(puhost, msc_struct->chin, (uint8_t *)&bot_trans->csw, + MSC_CSW_LEN); + bot_trans->bot_state = BOT_STATE_RECV_CSW_WAIT; + + break; + case BOT_STATE_RECV_CSW_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chin); + if(urb_status == URB_DONE) + { + bot_trans->bot_state = BOT_STATE_SEND_CBW; + bot_trans->cmd_state = CMD_STATE_SEND; + status = usbh_check_csw(uhost, &bot_trans->cbw, &bot_trans->csw); + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + + break; + case BOT_STATE_ERROR_IN: + clr_status = usbh_clear_ept_feature(puhost, msc_struct->eptin, msc_struct->chin); + if(clr_status == USB_OK) + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + usbh_set_toggle(puhost, msc_struct->chin, 0); + } + + break; + case BOT_STATE_ERROR_OUT: + clr_status = usbh_clear_ept_feature(puhost, msc_struct->eptout, msc_struct->chout); + if(clr_status == USB_OK) + { + usbh_set_toggle(puhost, msc_struct->chout, 1 - puhost->hch[msc_struct->chout].toggle_out); + usbh_set_toggle(puhost, msc_struct->chin, 0); + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + break; + case BOT_STATE_COMPLETE: + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host msc bulk-only get inquiry request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @param inquiry: to the structure of msc_scsi_data_inquiry + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_get_inquiry(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_inquiry *inquiry) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_INQUIRY_DATA_LEN, MSC_INQUIRY_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_inquiry(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only capacity request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @param capacity: to the structure of msc_scsi_data_capacity + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_capacity(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_capacity *capacity) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_CAPACITY10_DATA_LEN, MSC_CAPACITY10_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_capacity10(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + capacity->blk_nbr = bot_trans->buffer[3] | bot_trans->buffer[2] << 8 | + bot_trans->buffer[1] << 16 | bot_trans->buffer[0] << 24; + capacity->blk_size = bot_trans->buffer[7] | bot_trans->buffer[6] << 8 ; + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only tet unit ready request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_test_unit_ready(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_TEST_UNIT_READY_DATA_LEN, + MSC_TEST_UNIT_READY_CMD_LEN, MSC_CBW_FLAG_OUT); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_test_unit_ready(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only request sense request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_request_sense(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_REQUEST_SENSE_DATA_LEN, + MSC_REQUEST_SENSE_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_requset_sense(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only write request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param address: logical block address + * @param write_data: write data buffer + * @param write_len: write data length + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_write(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *write_data, + uint32_t write_len, uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, write_len * 512, + MSC_WRITE_CMD_LEN, MSC_CBW_FLAG_OUT); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_write(bot_trans, bot_trans->cbw.CBWCB, lun, write_len, address, write_data); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only read request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param address: logical block address + * @param read_data: read data buffer + * @param read_len: read data length + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_read(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *read_data, + uint32_t read_len, uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, read_len * 512, + MSC_READ_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_read(bot_trans, bot_trans->cbw.CBWCB, lun, read_len, address, read_data); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc init + * @param msc_struct: to the structure of usbh_msc_type + * @retval status: usb_sts_type status + */ +usb_sts_type msc_bot_scsi_init(usbh_msc_type *msc_struct) +{ + msc_struct->state = USBH_MSC_INIT; + msc_struct->ctrl_state = USBH_MSC_STATE_IDLE; + msc_struct->error = MSC_OK; + msc_struct->cur_lun = 0; + msc_struct->max_lun = 0; + msc_struct->use_lun = 0; + msc_struct->bot_trans.msc_struct = &usbh_msc; + msc_struct->bot_trans.cmd_state = CMD_STATE_SEND; + msc_struct->bot_trans.bot_state = BOT_STATE_SEND_CBW; + return USB_OK; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h new file mode 100644 index 0000000000..b62f0138f4 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h @@ -0,0 +1,239 @@ +/** + ************************************************************************** + * @file usbh_msc_bot_scsi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc bulk-only transfer and scsi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_BOT_SCSI_H +#define __USBH_MSC_BOT_SCSI_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_msc_bot_scsi_class + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class_definition + * @{ + */ + +#define MSC_CBW_SIGNATURE 0x43425355 +#define MSC_CSW_SIGNATURE 0x53425355 +#define MSC_CBW_TAG 0x50607080 +#define MSC_CBW_FLAG_IN 0x80 +#define MSC_CBW_FLAG_OUT 0x00 + +#define MSC_CBW_LEN 31 +#define MSC_CSW_LEN 13 +#define MSC_CBW_CB_LEN 16 +#define MSC_TEST_UNIT_READY_CMD_LEN 12 +#define MSC_TEST_UNIT_READY_DATA_LEN 0 +#define MSC_INQUIRY_CMD_LEN 12 +#define MSC_INQUIRY_DATA_LEN 36 +#define MSC_CAPACITY10_CMD_LEN 12 +#define MSC_CAPACITY10_DATA_LEN 8 +#define MSC_REQUEST_SENSE_CMD_LEN 12 +#define MSC_REQUEST_SENSE_DATA_LEN 18 +#define MSC_WRITE_CMD_LEN 12 +#define MSC_READ_CMD_LEN 10 + +#define MSC_OPCODE_INQUIRY 0x12 +#define MSC_OPCODE_CAPACITY 0x25 +#define MSC_OPCODE_TEST_UNIT_READY 0x00 +#define MSC_OPCODE_REQUEST_SENSE 0x03 +#define MSC_OPCODE_WRITE10 0x2A +#define MSC_OPCODE_READ10 0x28 + +typedef enum +{ + BOT_STATE_IDLE, + BOT_STATE_SEND_CBW, + BOT_STATE_SEND_CBW_WAIT, + BOT_STATE_DATA_IN, + BOT_STATE_DATA_IN_WAIT, + BOT_STATE_DATA_OUT, + BOT_STATE_DATA_OUT_WAIT, + BOT_STATE_RECV_CSW, + BOT_STATE_RECV_CSW_WAIT, + BOT_STATE_ERROR_IN, + BOT_STATE_ERROR_OUT, + BOT_STATE_COMPLETE +}msc_bot_state_type; + +typedef enum +{ + CMD_STATE_SEND, + CMD_STATE_WAIT, +}msc_cmd_state_type; + +/** + * @brief usb msc process state + */ +typedef enum +{ + USBH_MSC_INIT, + USBH_MSC_INQUIRY, + USBH_MSC_TEST_UNIT_READY, + USBH_MSC_READ_CAPACITY10, + USBH_MSC_REQUEST_SENSE, + USBH_MSC_READ10, + USBH_MSC_WRITE, + USBH_MSC_BUSY, + USBH_MSC_ERROR, + USBH_MSC_IDLE +}msc_state_type; + +typedef enum +{ + MSC_OK, + MSC_NOT_READY, + MSC_ERROR +}msc_error_type; + + +/** + * @brief usb msc inquiry data type + */ +typedef struct +{ + uint8_t pdev_type; + uint8_t rmb; + uint8_t version; + uint8_t data_format; + uint8_t length; + uint8_t reserved[3]; + uint8_t vendor[8]; + uint8_t product[16]; + uint8_t revision[4]; +}msc_scsi_data_inquiry; + + +/** + * @brief usb msc capacity data type + */ +typedef struct +{ + uint32_t blk_nbr; + uint32_t blk_size; +}msc_scsi_data_capacity; + +/** + * @brief usb msc bulk-only command block wrapper type + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTag; + uint32_t dCBWDataTransferLength; + uint8_t bmCBWFlags; + uint8_t bCBWLUN; + uint8_t bCBWCBLength; + uint8_t CBWCB[MSC_CBW_CB_LEN]; +}msc_bot_cbw_type; + +/** + * @brief usb msc bulk-only command status wrapper type + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTag; + uint32_t dCSWDataResidue; + uint8_t bCSWStatus; +}msc_bot_csw_type; + +/** + * @brief usb msc bulk-only transfer control type + */ +typedef struct +{ + uint8_t buffer[32]; + msc_bot_cbw_type cbw; + msc_bot_csw_type csw; + msc_cmd_state_type cmd_state; + msc_bot_state_type bot_state; + uint8_t *data; + void *msc_struct; +}msc_bot_trans_type; + +/** + * @brief usb msc bank type + */ +typedef struct +{ + msc_scsi_data_inquiry inquiry; + msc_scsi_data_capacity capacity; + msc_state_type state; + msc_error_type ready; + usb_sts_type pre_state; + uint8_t change; +}usbh_msc_unit_type; + + +usb_sts_type usb_bot_request(void *uhost, msc_bot_trans_type *bot_trans); + +usb_sts_type usbh_msc_bot_scsi_get_inquiry(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_inquiry *inquiry); + +usb_sts_type usbh_msc_bot_scsi_capacity(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_capacity *capacity); + +usb_sts_type usbh_msc_bot_scsi_test_unit_ready(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_request_sense(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_write(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *write_data, + uint32_t write_len, uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_read(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *read_data, + uint32_t read_len, uint8_t lun); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c new file mode 100644 index 0000000000..fd2532746a --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c @@ -0,0 +1,523 @@ +/** + ************************************************************************** + * @file usbh_msc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_msc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_msc_class + * @brief usb host class msc demo + * @{ + */ + +/** @defgroup USBH_msc_class_private_functions + * @{ + */ + +static usb_sts_type uhost_init_handler(void *uhost); +static usb_sts_type uhost_reset_handler(void *uhost); +static usb_sts_type uhost_request_handler(void *uhost); +static usb_sts_type uhost_process_handler(void *uhost); + +static usb_sts_type usbh_msc_get_max_lun(void *uhost, uint8_t *lun); +static usb_sts_type usbh_msc_clear_feature(void *uhost, uint8_t ept_num); + + +usbh_msc_type usbh_msc; + +usbh_class_handler_type uhost_msc_class_handler = +{ + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_msc +}; + + + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t if_x, eptidx = 0; + usbh_msc_type *pmsc = &usbh_msc; + puhost->class_handler->pdata = &usbh_msc; + + if_x = usbh_find_interface(puhost, USB_CLASS_CODE_MSC, MSC_SUBCLASS_SCSI_TRANS, MSC_PROTOCOL_BBB); + if(if_x == 0xFF) + { + USBH_DEBUG("Unsupport Device!"); + return USB_NOT_SUPPORT; + } + pmsc->protocol = puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceProtocol; + + for(eptidx = 0; eptidx < puhost->dev.cfg_desc.interface[if_x].interface.bNumEndpoints; eptidx ++) + { + if(puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress & 0x80) + { + pmsc->eptin = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress; + pmsc->in_maxpacket = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].wMaxPacketSize; + pmsc->in_poll = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bInterval; + + pmsc->chin = usbh_alloc_channel(puhost, pmsc->eptin); + /* enable channel */ + usbh_hc_open(puhost, pmsc->chin, pmsc->eptin, + puhost->dev.address, EPT_BULK_TYPE, + pmsc->in_maxpacket, + puhost->dev.speed); + } + else + { + pmsc->eptout = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress; + pmsc->out_maxpacket = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].wMaxPacketSize; + pmsc->out_poll = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bInterval; + + pmsc->chout = usbh_alloc_channel(puhost, pmsc->eptout); + /* enable channel */ + usbh_hc_open(puhost, pmsc->chout,pmsc->eptout, + puhost->dev.address, EPT_BULK_TYPE, + pmsc->out_maxpacket, + puhost->dev.speed); + } + } + + msc_bot_scsi_init(pmsc); + usbh_set_toggle(puhost, pmsc->chout, 0); + usbh_set_toggle(puhost, pmsc->chin, 0); + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + uint8_t i_index = 0; + + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + for(i_index = 0; i_index < pmsc->max_lun ; i_index ++) + { + pmsc->l_unit_n[i_index].pre_state = USB_FAIL; + pmsc->l_unit_n[i_index].change = 0; + pmsc->l_unit_n[i_index].state = USBH_MSC_INIT; + pmsc->l_unit_n[i_index].ready = MSC_NOT_READY; + } + + if(pmsc->chin != 0 ) + { + usbh_free_channel(puhost, pmsc->chin); + usbh_ch_disable(puhost, pmsc->chin); + pmsc->chin = 0; + } + + if(pmsc->chout != 0 ) + { + usbh_free_channel(puhost, pmsc->chout); + usbh_ch_disable(puhost, pmsc->chout); + pmsc->chout = 0; + } + + return status; +} + +/** + * @brief usb host hid class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + uint8_t i_index = 0; + + switch(pmsc->ctrl_state) + { + case USBH_MSC_STATE_IDLE: + pmsc->ctrl_state = USBH_MSC_STATE_GET_LUN; + break; + case USBH_MSC_STATE_GET_LUN: + if((status = usbh_msc_get_max_lun(uhost, (uint8_t *)&pmsc->max_lun)) == USB_OK) + { + pmsc->max_lun = (pmsc->max_lun & 0xFF) > USBH_SUPPORT_MAX_LUN ? USBH_SUPPORT_MAX_LUN:((pmsc->max_lun & 0xFF) + 1); + USBH_DEBUG("Support max lun %d", pmsc->max_lun); + for(i_index = 0; i_index < pmsc->max_lun ; i_index ++) + { + pmsc->l_unit_n[i_index].pre_state = USB_FAIL; + pmsc->l_unit_n[i_index].change = 0; + pmsc->l_unit_n[i_index].state = USBH_MSC_INIT; + } + } + break; + case USBH_MSC_STATE_ERROR: + if((usbh_msc_clear_feature(uhost, 0)) == USB_OK) + { + pmsc->ctrl_state = USBH_MSC_STATE_GET_LUN; + } + break; + default: + break; + } + + return status; +} + +/** + * @brief usb host class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint64_t msize = 0; + usb_sts_type status; + switch(pmsc->state) + { + case USBH_MSC_INIT: + if(pmsc->cur_lun < pmsc->max_lun) + { + switch(pmsc->l_unit_n[pmsc->cur_lun].state) + { + case USBH_MSC_INIT: + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_INQUIRY; + break; + case USBH_MSC_INQUIRY: + status = usbh_msc_bot_scsi_get_inquiry(uhost, &pmsc->bot_trans, pmsc->cur_lun, &pmsc->l_unit_n[pmsc->cur_lun].inquiry); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_TEST_UNIT_READY; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + } + break; + case USBH_MSC_TEST_UNIT_READY: + status = usbh_msc_bot_scsi_test_unit_ready(uhost, &pmsc->bot_trans, pmsc->cur_lun); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_READ_CAPACITY10; + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_OK; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + } + break; + + case USBH_MSC_READ_CAPACITY10: + status = usbh_msc_bot_scsi_capacity(uhost, &pmsc->bot_trans, pmsc->cur_lun, &pmsc->l_unit_n[pmsc->cur_lun].capacity); + if(status == USB_OK) + { + msize = (uint64_t)pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_nbr * (uint64_t)pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_size; + USBH_DEBUG("Device capacity: %llu Byte", msize); + USBH_DEBUG("Block num: %d ", pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_nbr); + USBH_DEBUG("Block size: %d Byte", pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_size); + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_IDLE; + pmsc->cur_lun ++; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + } + break; + case USBH_MSC_REQUEST_SENSE: + status = usbh_msc_bot_scsi_request_sense(uhost, &pmsc->bot_trans, pmsc->cur_lun); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_TEST_UNIT_READY; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_ERROR; + } + break; + + case USBH_MSC_BUSY: + break; + case USBH_MSC_ERROR: + break; + default: + break; + } + + } + else + { + pmsc->state = USBH_MSC_IDLE; + } + break; + case USBH_MSC_IDLE: + if(puhost->user_handler->user_application != NULL) + { + puhost->user_handler->user_application(); + } + default: + break; + } + return USB_OK; +} + + +/** + * @brief usb host msc get max lun + * @param uhost: to the structure of usbh_core_type + * @param lun: max lun buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_msc_get_max_lun(void *uhost, uint8_t *lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_D2H | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = MSC_REQ_GET_MAX_LUN; + puhost->ctrl.setup.wValue = 0; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 1; + usbh_ctrl_request(puhost, lun, 1); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host msc clear feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_msc_clear_feature(void *uhost, uint8_t ept_num) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + puhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + puhost->ctrl.setup.wValue = 0; + puhost->ctrl.setup.wIndex = ept_num; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host msc clear feature + * @param lun: logical unit number + * @retval msc_error_type status + */ +msc_error_type usbh_msc_is_ready(void *uhost, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + return pmsc->l_unit_n[lun].ready; +} + + +/** + * @brief usb host msc read and write handle + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_rw_handle(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + switch(pmsc->l_unit_n[lun].state) + { + case USBH_MSC_READ10: + status = usbh_msc_bot_scsi_read(uhost, &pmsc->bot_trans, address, buffer, len, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[lun].state = USBH_MSC_REQUEST_SENSE; + status = USB_WAIT; + } + break; + case USBH_MSC_WRITE: + status = usbh_msc_bot_scsi_write(uhost, &pmsc->bot_trans, address, buffer, len, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[lun].state = USBH_MSC_REQUEST_SENSE; + status = USB_WAIT; + } + break; + case USBH_MSC_REQUEST_SENSE: + status = usbh_msc_bot_scsi_request_sense(uhost, &pmsc->bot_trans, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + status = USB_FAIL; + } + else if(status == USB_FAIL) + { + USBH_DEBUG("device not support"); + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc read + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_read(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint32_t timeout = 0; + if(puhost->conn_sts == 0 || puhost->global_state != USBH_CLASS + || pmsc->l_unit_n[lun].state != USBH_MSC_IDLE) + { + return USB_FAIL; + } + pmsc->bot_trans.msc_struct = &usbh_msc; + pmsc->l_unit_n[lun].state = USBH_MSC_READ10; + pmsc->use_lun = lun; + + timeout = puhost->timer; + + while(usbh_msc_rw_handle(uhost, address, len, buffer, lun) == USB_WAIT) + { + if(puhost->conn_sts == 0 || (puhost->timer - timeout) > (len * 10000)) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + return USB_FAIL; + } + } + return USB_OK; +} + +/** + * @brief usb host msc write + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_write(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint32_t timeout = 0; + if(puhost->conn_sts == 0 || puhost->global_state != USBH_CLASS + || pmsc->l_unit_n[lun].state != USBH_MSC_IDLE) + { + return USB_FAIL; + } + + pmsc->bot_trans.msc_struct = &usbh_msc; + pmsc->l_unit_n[lun].state = USBH_MSC_WRITE; + pmsc->use_lun = lun; + + timeout = puhost->timer; + while(usbh_msc_rw_handle(uhost, address, len, buffer, lun) == USB_WAIT) + { + if(puhost->conn_sts == 0 || (puhost->timer - timeout) > (len * 10000)) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + return USB_FAIL; + } + } + return USB_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h new file mode 100644 index 0000000000..9435f0f1fa --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h @@ -0,0 +1,143 @@ +/** + ************************************************************************** + * @file usbh_msc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_CLASS_H +#define __USBH_MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" +#include "usbh_msc_bot_scsi.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_msc_class + * @{ + */ + +/** @defgroup USBH_msc_class_definition + * @{ + */ + +/** + * @brief usb msc subclass code + */ +#define MSC_SUBCLASS_SCSI_TRANS 0x06 + +/** + * @brief usb msc protocol code + */ +#define MSC_PROTOCOL_BBB 0x50 + +/** + * @brief usb msc request code + */ +#define MSC_REQ_GET_MAX_LUN 0xFE +#define MSC_REQ_BOMSR 0xFF + +/** + * @brief usb hid request code + */ +#define USB_HID_GET_REPORT 0x01 +#define USB_HID_GET_IDLE 0x02 +#define USB_HID_GET_PROTOCOL 0x03 +#define USB_HID_SET_REPORT 0x09 +#define USB_HID_SET_IDLE 0x0A +#define USB_HID_SET_PROTOCOL 0x0B + + +#define USBH_SUPPORT_MAX_LUN 0x2 + +/** + * @brief usb msc request state + */ +typedef enum +{ + USBH_MSC_STATE_IDLE, + USBH_MSC_STATE_GET_LUN, + USBH_MSC_STATE_ERROR, + USBH_MSC_STATE_COMPLETE, +}usbh_msc_ctrl_state_type; + +/** + * @brief usb msc struct + */ +typedef struct +{ + uint8_t chin; + uint8_t eptin; + uint16_t in_maxpacket; + uint8_t in_poll; + + uint8_t chout; + uint8_t eptout; + uint16_t out_maxpacket; + uint8_t out_poll; + uint8_t protocol; + + uint32_t max_lun; + uint32_t cur_lun; + uint32_t use_lun; + + + usbh_msc_ctrl_state_type ctrl_state; + msc_state_type state; + uint8_t error; + msc_bot_trans_type bot_trans; + usbh_msc_unit_type l_unit_n[USBH_SUPPORT_MAX_LUN]; + uint16_t poll_timer; + uint8_t buffer[64]; +}usbh_msc_type; + +extern usbh_class_handler_type uhost_msc_class_handler; +extern usbh_msc_type usbh_msc; +msc_error_type usbh_msc_is_ready(void *uhost, uint8_t lun); +usb_sts_type usbh_msc_write(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type usbh_msc_read(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type usbh_msc_rw_handle(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type msc_bot_scsi_init(usbh_msc_type *msc_struct); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h new file mode 100644 index 0000000000..9bdf135cd6 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h @@ -0,0 +1,219 @@ +/** + ************************************************************************** + * @file usb_conf.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CONF_H +#define __USB_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "at32f435_437_usb.h" +#include "at32f435_437.h" + +/** @addtogroup AT32F437_periph_examples + * @{ + */ + +/** @addtogroup 437_USB_device_hid_app_led3 + * @{ + */ + +/** + * @brief enable usb device mode + */ +#define USE_OTG_DEVICE_MODE + +/** + * @brief enable usb host mode + */ +/* #define USE_OTG_HOST_MODE */ + +/** + * @brief select otgfs1 or otgfs2 define + */ + +/* use otgfs1 */ +#define OTG_USB_ID 1 + +/* use otgfs2 */ +/* #define OTG_USB_ID 2 */ + +#if (OTG_USB_ID == 1) +#define USB_ID 0 +#define OTG_CLOCK CRM_OTGFS1_PERIPH_CLOCK +#define OTG_IRQ OTGFS1_IRQn +#define OTG_IRQ_HANDLER OTGFS1_IRQHandler +#define OTG_WKUP_IRQ OTGFS1_WKUP_IRQn +#define OTG_WKUP_HANDLER OTGFS1_WKUP_IRQHandler +#define OTG_WKUP_EXINT_LINE EXINT_LINE_18 + +#define OTG_PIN_GPIO GPIOA +#define OTG_PIN_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK + +#define OTG_PIN_DP GPIO_PINS_12 +#define OTG_PIN_DP_SOURCE GPIO_PINS_SOURCE12 + +#define OTG_PIN_DM GPIO_PINS_11 +#define OTG_PIN_DM_SOURCE GPIO_PINS_SOURCE11 + +#define OTG_PIN_VBUS GPIO_PINS_9 +#define OTG_PIN_VBUS_SOURCE GPIO_PINS_SOURCE9 + +#define OTG_PIN_ID GPIO_PINS_10 +#define OTG_PIN_ID_SOURCE GPIO_PINS_SOURCE10 + +#define OTG_PIN_SOF_GPIO GPIOA +#define OTG_PIN_SOF_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK +#define OTG_PIN_SOF GPIO_PINS_8 +#define OTG_PIN_SOF_SOURCE GPIO_PINS_SOURCE8 + +#define OTG_PIN_MUX GPIO_MUX_10 +#endif + +#if (OTG_USB_ID == 2) +#define USB_ID 1 +#define OTG_CLOCK CRM_OTGFS2_PERIPH_CLOCK +#define OTG_IRQ OTGFS2_IRQn +#define OTG_IRQ_HANDLER OTGFS2_IRQHandler +#define OTG_WKUP_IRQ OTGFS2_WKUP_IRQn +#define OTG_WKUP_HANDLER OTGFS2_WKUP_IRQHandler +#define OTG_WKUP_EXINT_LINE EXINT_LINE_20 + +#define OTG_PIN_GPIO GPIOB +#define OTG_PIN_GPIO_CLOCK CRM_GPIOB_PERIPH_CLOCK + +#define OTG_PIN_DP GPIO_PINS_15 +#define OTG_PIN_DP_SOURCE GPIO_PINS_SOURCE15 + +#define OTG_PIN_DM GPIO_PINS_14 +#define OTG_PIN_DM_SOURCE GPIO_PINS_SOURCE14 + +#define OTG_PIN_VBUS GPIO_PINS_13 +#define OTG_PIN_VBUS_SOURCE GPIO_PINS_SOURCE13 + +#define OTG_PIN_ID GPIO_PINS_12 +#define OTG_PIN_ID_SOURCE GPIO_PINS_SOURCE10 + +#define OTG_PIN_SOF_GPIO GPIOA +#define OTG_PIN_SOF_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK +#define OTG_PIN_SOF GPIO_PINS_4 +#define OTG_PIN_SOF_SOURCE GPIO_PINS_SOURCE4 + +#define OTG_PIN_MUX GPIO_MUX_12 +#endif + +/** + * @brief usb device mode config + */ +#ifdef USE_OTG_DEVICE_MODE +/** + * @brief usb device mode fifo + */ +/* otg1 device fifo */ +#define USBD_RX_SIZE 128 +#define USBD_EP0_TX_SIZE 24 +#define USBD_EP1_TX_SIZE 20 +#define USBD_EP2_TX_SIZE 20 +#define USBD_EP3_TX_SIZE 20 +#define USBD_EP4_TX_SIZE 20 +#define USBD_EP5_TX_SIZE 20 +#define USBD_EP6_TX_SIZE 20 +#define USBD_EP7_TX_SIZE 20 + +/* otg2 device fifo */ +#define USBD2_RX_SIZE 128 +#define USBD2_EP0_TX_SIZE 24 +#define USBD2_EP1_TX_SIZE 20 +#define USBD2_EP2_TX_SIZE 20 +#define USBD2_EP3_TX_SIZE 20 +#define USBD2_EP4_TX_SIZE 20 +#define USBD2_EP5_TX_SIZE 20 +#define USBD2_EP6_TX_SIZE 20 +#define USBD2_EP7_TX_SIZE 20 + +/** + * @brief usb endpoint max num define + */ +#ifndef USB_EPT_MAX_NUM +#define USB_EPT_MAX_NUM 8 +#endif +#endif + +/** + * @brief usb host mode config + */ +#ifdef USE_OTG_HOST_MODE +#ifndef USB_HOST_CHANNEL_NUM +#define USB_HOST_CHANNEL_NUM 16 +#endif + +/** + * @brief usb host mode fifo + */ +/* otg1 host fifo */ +#define USBH_RX_FIFO_SIZE 128 +#define USBH_NP_TX_FIFO_SIZE 96 +#define USBH_P_TX_FIFO_SIZE 96 + +/* otg2 host fifo */ +#define USBH2_RX_FIFO_SIZE 128 +#define USBH2_NP_TX_FIFO_SIZE 96 +#define USBH2_P_TX_FIFO_SIZE 96 +#endif + +/** + * @brief usb sof output enable + */ +/* #define USB_SOF_OUTPUT_ENABLE */ + +/** + * @brief usb vbus ignore + */ +#define USB_VBUS_IGNORE + +/** + * @brief usb low power wakeup handler enable + */ +/* #define USB_LOW_POWER_WAKUP */ + +void usb_delay_ms(uint32_t ms); +void usb_delay_us(uint32_t us); + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h new file mode 100644 index 0000000000..5ab69918cd --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h @@ -0,0 +1,136 @@ +/** + ************************************************************************** + * @file usb_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CORE_H +#define __USB_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "usb_std.h" +#include "usb_conf.h" + +#ifdef USE_OTG_DEVICE_MODE +#include "usbd_core.h" +#endif +#ifdef USE_OTG_HOST_MODE +#include "usbh_core.h" +#endif + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @addtogroup USB_drivers_core + * @{ + */ + +/** @defgroup USB_core_exported_types + * @{ + */ + +/** + * @brief usb core speed select + */ +typedef enum +{ + USB_LOW_SPEED_CORE_ID, /*!< usb low speed core id */ + USB_FULL_SPEED_CORE_ID, /*!< usb full speed core id */ + USB_HIGH_SPEED_CORE_ID, /*!< usb high speed core id */ +} usb_speed_type; + +/** + * @brief usb core cofig struct + */ +typedef struct +{ + uint8_t speed; /*!< otg speed */ + uint8_t dma_en; /*!< dma enable state, not use*/ + uint8_t hc_num; /*!< the otg host support number of channel */ + uint8_t ept_num; /*!< the otg device support number of endpoint */ + + uint16_t max_size; /*!< support max packet size */ + uint16_t fifo_size; /*!< the usb otg total file size */ + uint8_t phy_itface; /*!< usb phy select */ + uint8_t core_id; /*!< the usb otg core id */ + uint8_t low_power; /*!< the usb otg low power option */ + uint8_t sof_out; /*!< the sof signal output */ + uint8_t usb_id; /*!< select otgfs1 or otgfs2 */ + uint8_t vbusig; /*!< vbus ignore */ +} usb_core_cfg; + +/** + * @brief usb otg core struct type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< the usb otg register type */ +#ifdef USE_OTG_DEVICE_MODE + usbd_core_type dev; /*!< the usb device core type */ +#endif + +#ifdef USE_OTG_HOST_MODE + usbh_core_type host; /*!< the usb host core type */ +#endif + + usb_core_cfg cfg; /*!< the usb otg core config type */ + +} otg_core_type; + +usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id); +#ifdef USE_OTG_DEVICE_MODE +usb_sts_type usbd_init(otg_core_type *udev, + uint8_t core_id, uint8_t usb_id, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler); +#endif + +#ifdef USE_OTG_HOST_MODE +usb_sts_type usbh_init(otg_core_type *hdev, + uint8_t core_id, uint8_t usb_id, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler); +#endif +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h new file mode 100644 index 0000000000..278edb259d --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h @@ -0,0 +1,385 @@ +/** + ************************************************************************** + * @file usb_std.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb standard header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_STD_H +#define __USB_STD_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @addtogroup USB_standard + * @{ + */ + +/** @defgroup USB_standard_define + * @{ + */ + +/** + * @brief usb request recipient + */ +#define USB_REQ_RECIPIENT_DEVICE 0x00 /*!< usb request recipient device */ +#define USB_REQ_RECIPIENT_INTERFACE 0x01 /*!< usb request recipient interface */ +#define USB_REQ_RECIPIENT_ENDPOINT 0x02 /*!< usb request recipient endpoint */ +#define USB_REQ_RECIPIENT_OTHER 0x03 /*!< usb request recipient other */ +#define USB_REQ_RECIPIENT_MASK 0x1F /*!< usb request recipient mask */ + +/** + * @brief usb request type + */ +#define USB_REQ_TYPE_STANDARD 0x00 /*!< usb request type standard */ +#define USB_REQ_TYPE_CLASS 0x20 /*!< usb request type class */ +#define USB_REQ_TYPE_VENDOR 0x40 /*!< usb request type vendor */ +#define USB_REQ_TYPE_RESERVED 0x60 /*!< usb request type reserved */ + +/** + * @brief usb request data transfer direction + */ +#define USB_REQ_DIR_HTD 0x00 /*!< usb request data transfer direction host to device */ +#define USB_REQ_DIR_DTH 0x80 /*!< usb request data transfer direction device to host */ + +/** + * @brief usb standard device requests codes + */ +#define USB_STD_REQ_GET_STATUS 0 /*!< usb request code status */ +#define USB_STD_REQ_CLEAR_FEATURE 1 /*!< usb request code clear feature */ +#define USB_STD_REQ_SET_FEATURE 3 /*!< usb request code feature */ +#define USB_STD_REQ_SET_ADDRESS 5 /*!< usb request code address */ +#define USB_STD_REQ_GET_DESCRIPTOR 6 /*!< usb request code get descriptor */ +#define USB_STD_REQ_SET_DESCRIPTOR 7 /*!< usb request code set descriptor */ +#define USB_STD_REQ_GET_CONFIGURATION 8 /*!< usb request code get configuration */ +#define USB_STD_REQ_SET_CONFIGURATION 9 /*!< usb request code set configuration */ +#define USB_STD_REQ_GET_INTERFACE 10 /*!< usb request code get interface */ +#define USB_STD_REQ_SET_INTERFACE 11 /*!< usb request code set interface */ +#define USB_STD_REQ_SYNCH_FRAME 12 /*!< usb request code synch frame */ + +/** + * @brief usb standard device type + */ +#define USB_DESCIPTOR_TYPE_DEVICE 1 /*!< usb standard device type device */ +#define USB_DESCIPTOR_TYPE_CONFIGURATION 2 /*!< usb standard device type configuration */ +#define USB_DESCIPTOR_TYPE_STRING 3 /*!< usb standard device type string */ +#define USB_DESCIPTOR_TYPE_INTERFACE 4 /*!< usb standard device type interface */ +#define USB_DESCIPTOR_TYPE_ENDPOINT 5 /*!< usb standard device type endpoint */ +#define USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER 6 /*!< usb standard device type qualifier */ +#define USB_DESCIPTOR_TYPE_OTHER_SPEED 7 /*!< usb standard device type other speed */ +#define USB_DESCIPTOR_TYPE_INTERFACE_POWER 8 /*!< usb standard device type interface power */ + +/** + * @brief usb standard string type + */ +#define USB_LANGID_STRING 0 /*!< usb standard string type lang id */ +#define USB_MFC_STRING 1 /*!< usb standard string type mfc */ +#define USB_PRODUCT_STRING 2 /*!< usb standard string type product */ +#define USB_SERIAL_STRING 3 /*!< usb standard string type serial */ +#define USB_CONFIG_STRING 4 /*!< usb standard string type config */ +#define USB_INTERFACE_STRING 5 /*!< usb standard string type interface */ + +/** + * @brief usb configuration attributes + */ +#define USB_CONF_REMOTE_WAKEUP 2 /*!< usb configuration attributes remote wakeup */ +#define USB_CONF_SELF_POWERED 1 /*!< usb configuration attributes self powered */ + +/** + * @brief usb standard feature selectors + */ +#define USB_FEATURE_EPT_HALT 0 /*!< usb standard feature selectors endpoint halt */ +#define USB_FEATURE_REMOTE_WAKEUP 1 /*!< usb standard feature selectors remote wakeup */ +#define USB_FEATURE_TEST_MODE 2 /*!< usb standard feature selectors test mode */ + +/** + * @brief usb device connect state + */ +typedef enum +{ + USB_CONN_STATE_DEFAULT =1, /*!< usb device connect state default */ + USB_CONN_STATE_ADDRESSED, /*!< usb device connect state address */ + USB_CONN_STATE_CONFIGURED, /*!< usb device connect state configured */ + USB_CONN_STATE_SUSPENDED /*!< usb device connect state suspend */ +}usbd_conn_state; + +/** + * @brief endpoint 0 state + */ +#define USB_EPT0_IDLE 0 /*!< usb endpoint state idle */ +#define USB_EPT0_SETUP 1 /*!< usb endpoint state setup */ +#define USB_EPT0_DATA_IN 2 /*!< usb endpoint state data in */ +#define USB_EPT0_DATA_OUT 3 /*!< usb endpoint state data out */ +#define USB_EPT0_STATUS_IN 4 /*!< usb endpoint state status in */ +#define USB_EPT0_STATUS_OUT 5 /*!< usb endpoint state status out */ +#define USB_EPT0_STALL 6 /*!< usb endpoint state stall */ + +/** + * @brief usb descriptor length + */ +#define USB_DEVICE_QUALIFIER_DESC_LEN 0x0A /*!< usb qualifier descriptor length */ +#define USB_DEVICE_DESC_LEN 0x12 /*!< usb device descriptor length */ +#define USB_DEVICE_CFG_DESC_LEN 0x09 /*!< usb configuration descriptor length */ +#define USB_DEVICE_IF_DESC_LEN 0x09 /*!< usb interface descriptor length */ +#define USB_DEVICE_EPT_LEN 0x07 /*!< usb endpoint descriptor length */ +#define USB_DEVICE_OTG_DESC_LEN 0x03 /*!< usb otg descriptor length */ +#define USB_DEVICE_LANGID_STR_DESC_LEN 0x04 /*!< usb lang id string descriptor length */ +#define USB_DEVICE_OTHER_SPEED_DESC_SIZ_LEN 0x09 /*!< usb other speed descriptor length */ + +/** + * @brief usb class code + */ +#define USB_CLASS_CODE_AUDIO 0x01 /*!< usb class code audio */ +#define USB_CLASS_CODE_CDC 0x02 /*!< usb class code cdc */ +#define USB_CLASS_CODE_HID 0x03 /*!< usb class code hid */ +#define USB_CLASS_CODE_PRINTER 0x07 /*!< usb class code printer */ +#define USB_CLASS_CODE_MSC 0x08 /*!< usb class code msc */ +#define USB_CLASS_CODE_HUB 0x09 /*!< usb class code hub */ +#define USB_CLASS_CODE_CDCDATA 0x0A /*!< usb class code cdc data */ +#define USB_CLASS_CODE_CCID 0x0B /*!< usb class code ccid */ +#define USB_CLASS_CODE_VIDEO 0x0E /*!< usb class code video */ +#define USB_CLASS_CODE_VENDOR 0xFF /*!< usb class code vendor */ + +/** + * @brief usb endpoint type + */ +#define USB_EPT_DESC_CONTROL 0x00 /*!< usb endpoint description type control */ +#define USB_EPT_DESC_ISO 0x01 /*!< usb endpoint description type iso */ +#define USB_EPT_DESC_BULK 0x02 /*!< usb endpoint description type bulk */ +#define USB_EPT_DESC_INTERRUPT 0x03 /*!< usb endpoint description type interrupt */ + +#define USB_EPT_DESC_NSYNC 0x00 /*!< usb endpoint description nsync */ +#define USB_ETP_DESC_ASYNC 0x04 /*!< usb endpoint description async */ +#define USB_ETP_DESC_ADAPTIVE 0x08 /*!< usb endpoint description adaptive */ +#define USB_ETP_DESC_SYNC 0x0C /*!< usb endpoint description sync */ + +#define USB_EPT_DESC_DATA_EPT 0x00 /*!< usb endpoint description data */ +#define USB_EPT_DESC_FD_EPT 0x10 /*!< usb endpoint description fd */ +#define USB_EPT_DESC_FDDATA_EPT 0x20 /*!< usb endpoint description fddata */ + +/** + * @brief usb cdc class descriptor define + */ +#define USBD_CDC_CS_INTERFACE 0x24 +#define USBD_CDC_CS_ENDPOINT 0x25 + +/** + * @brief usb cdc class sub-type define + */ +#define USBD_CDC_SUBTYPE_HEADER 0x00 +#define USBD_CDC_SUBTYPE_CMF 0x01 +#define USBD_CDC_SUBTYPE_ACM 0x02 +#define USBD_CDC_SUBTYPE_UFD 0x06 + +/** + * @brief usb cdc class request code define + */ +#define SET_LINE_CODING 0x20 +#define GET_LINE_CODING 0x21 + +/** + * @brief usb cdc class set line coding struct + */ +typedef struct +{ + uint32_t bitrate; /* line coding baud rate */ + uint8_t format; /* line coding foramt */ + uint8_t parity; /* line coding parity */ + uint8_t data; /* line coding data bit */ +}linecoding_type; + +/** + * @brief usb hid class descriptor define + */ +#define HID_CLASS_DESC_HID 0x21 +#define HID_CLASS_DESC_REPORT 0x22 +#define HID_CLASS_DESC_PHYSICAL 0x23 + +/** + * @brief usb hid class request code define + */ +#define HID_REQ_SET_PROTOCOL 0x0B +#define HID_REQ_GET_PROTOCOL 0x03 +#define HID_REQ_SET_IDLE 0x0A +#define HID_REQ_GET_IDLE 0x02 +#define HID_REQ_SET_REPORT 0x09 +#define HID_REQ_GET_REPORT 0x01 +#define HID_DESCRIPTOR_TYPE 0x21 +#define HID_REPORT_DESC 0x22 + +/** + * @brief endpoint 0 max size + */ +#define USB_MAX_EP0_SIZE 64 /*!< usb endpoint 0 max size */ + +/** + * @brief usb swap address + */ +#define SWAPBYTE(addr) (uint16_t)(((uint16_t)(*((uint8_t *)(addr)))) + \ + (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) /*!< swap address */ + +/** + * @brief min and max define + */ +#define MIN(a, b) (uint16_t)(((a) < (b)) ? (a) : (b)) /*!< min define*/ +#define MAX(a, b) (uint16_t)(((a) > (b)) ? (a) : (b)) /*!< max define*/ + +/** + * @brief low byte and high byte define + */ +#define LBYTE(x) ((uint8_t)(x & 0x00FF)) /*!< low byte define */ +#define HBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) /*!< high byte define*/ + +/** + * @brief usb return status + */ +typedef enum +{ + USB_OK, /*!< usb status ok */ + USB_FAIL, /*!< usb status fail */ + USB_WAIT, /*!< usb status wait */ + USB_NOT_SUPPORT, /*!< usb status not support */ + USB_ERROR, /*!< usb status error */ +}usb_sts_type; + + +/** + * @brief format of usb setup data + */ +typedef struct +{ + uint8_t bmRequestType; /*!< characteristics of request */ + uint8_t bRequest; /*!< specific request */ + uint16_t wValue; /*!< word-sized field that varies according to request */ + uint16_t wIndex; /*!< word-sized field that varies according to request + typically used to pass an index or offset */ + uint16_t wLength; /*!< number of bytes to transfer if there is a data stage */ +} usb_setup_type; + +/** + * @brief format of standard device descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< device descriptor type */ + uint16_t bcdUSB; /*!< usb specification release number */ + uint8_t bDeviceClass; /*!< class code (assigned by the usb-if) */ + uint8_t bDeviceSubClass; /*!< subclass code (assigned by the usb-if) */ + uint8_t bDeviceProtocol; /*!< protocol code ((assigned by the usb-if)) */ + uint8_t bMaxPacketSize0; /*!< maximum packet size for endpoint zero */ + uint16_t idVendor; /*!< verndor id ((assigned by the usb-if)) */ + uint16_t idProduct; /*!< product id ((assigned by the usb-if)) */ + uint16_t bcdDevice; /*!< device release number in binary-coded decimal */ + uint8_t iManufacturer; /*!< index of string descriptor describing manufacturer */ + uint8_t iProduct; /*!< index of string descriptor describing product */ + uint8_t iSerialNumber; /*!< index of string descriptor describing serial number */ + uint8_t bNumConfigurations; /*!< number of possible configurations */ +} usb_device_desc_type; + +/** + * @brief format of standard configuration descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< configuration descriptor type */ + uint16_t wTotalLength; /*!< total length of data returned for this configuration */ + uint8_t bNumInterfaces; /*!< number of interfaces supported by this configuration */ + uint8_t bConfigurationValue; /*!< value to use as an argument to the SetConfiguration() request */ + uint8_t iConfiguration; /*!< index of string descriptor describing this configuration */ + uint8_t bmAttributes; /*!< configuration characteristics + D7 reserved + D6 self-powered + D5 remote wakeup + D4~D0 reserved */ + uint8_t bMaxPower; /*!< maximum power consumption of the usb device from the bus */ + + +}usb_configuration_desc_type; + +/** + * @brief format of standard interface descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< interface descriptor type */ + uint8_t bInterfaceNumber; /*!< number of this interface */ + uint8_t bAlternateSetting; /*!< value used to select this alternate setting for the interface */ + uint8_t bNumEndpoints; /*!< number of endpoints used by this interface */ + uint8_t bInterfaceClass; /*!< class code (assigned by the usb-if) */ + uint8_t bInterfaceSubClass; /*!< subclass code (assigned by the usb-if) */ + uint8_t bInterfaceProtocol; /*!< protocol code (assigned by the usb-if) */ + uint8_t iInterface; /*!< index of string descriptor describing this interface */ +} usb_interface_desc_type; + +/** + * @brief format of standard endpoint descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< endpoint descriptor type */ + uint8_t bEndpointAddress; /*!< the address of the endpoint on the usb device described by this descriptor */ + uint8_t bmAttributes; /*!< describes the endpoints attributes when it is configured using bConfiguration value */ + uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint */ + uint8_t bInterval; /*!< interval for polling endpoint for data transfers */ +} usb_endpoint_desc_type; + +/** + * @brief format of header + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< descriptor type */ +} usb_header_desc_type; + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h new file mode 100644 index 0000000000..35bdddc2ce --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h @@ -0,0 +1,187 @@ +/** + ************************************************************************** + * @file usbd_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb device core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_CORE_H +#define __USBD_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "usb_conf.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_core + * @{ + */ + +/** @defgroup USBD_core_exported_types + * @{ + */ + +#ifdef USE_OTG_DEVICE_MODE + +/** + * @brief usb device event + */ +typedef enum +{ + USBD_NOP_EVENT, /*!< usb device nop event */ + USBD_RESET_EVENT, /*!< usb device reset event */ + USBD_SUSPEND_EVENT, /*!< usb device suspend event */ + USBD_WAKEUP_EVENT, /*!< usb device wakeup event */ + USBD_DISCONNECT_EVNET, /*!< usb device disconnect event */ + USBD_INISOINCOM_EVENT, /*!< usb device inisoincom event */ + USBD_OUTISOINCOM_EVENT, /*!< usb device outisoincom event */ + USBD_ERR_EVENT /*!< usb device error event */ +}usbd_event_type; + +/** + * @brief usb device descriptor struct + */ +typedef struct +{ + uint16_t length; /*!< descriptor length */ + uint8_t *descriptor; /*!< descriptor string */ +}usbd_desc_t; + +/** + * @brief usb device descriptor handler + */ +typedef struct +{ + usbd_desc_t *(*get_device_descriptor)(void); /*!< get device descriptor callback */ + usbd_desc_t *(*get_device_qualifier)(void); /*!< get device qualifier callback */ + usbd_desc_t *(*get_device_configuration)(void); /*!< get device configuration callback */ + usbd_desc_t *(*get_device_other_speed)(void); /*!< get device other speed callback */ + usbd_desc_t *(*get_device_lang_id)(void); /*!< get device lang id callback */ + usbd_desc_t *(*get_device_manufacturer_string)(void); /*!< get device manufacturer callback */ + usbd_desc_t *(*get_device_product_string)(void); /*!< get device product callback */ + usbd_desc_t *(*get_device_serial_string)(void); /*!< get device serial callback */ + usbd_desc_t *(*get_device_interface_string)(void); /*!< get device interface string callback */ + usbd_desc_t *(*get_device_config_string)(void); /*!< get device device config callback */ +}usbd_desc_handler; + +/** + * @brief usb device class handler + */ +typedef struct +{ + usb_sts_type (*init_handler)(void *udev); /*!< usb class init handler */ + usb_sts_type (*clear_handler)(void *udev); /*!< usb class clear handler */ + usb_sts_type (*setup_handler)(void *udev, usb_setup_type *setup); /*!< usb class setup handler */ + usb_sts_type (*ept0_tx_handler)(void *udev); /*!< usb class endpoint 0 tx complete handler */ + usb_sts_type (*ept0_rx_handler)(void *udev); /*!< usb class endpoint 0 rx complete handler */ + usb_sts_type (*in_handler)(void *udev, uint8_t ept_num); /*!< usb class in transfer complete handler */ + usb_sts_type (*out_handler)(void *udev, uint8_t ept_num); /*!< usb class out transfer complete handler */ + usb_sts_type (*sof_handler)(void *udev); /*!< usb class sof handler */ + usb_sts_type (*event_handler)(void *udev, usbd_event_type event); /*!< usb class event handler */ + void *pdata; /*!< usb class data pointer */ +}usbd_class_handler; + +/** + * @brief usb device core struct type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< usb register pointer */ + + usbd_class_handler *class_handler; /*!< usb device class handler pointer */ + usbd_desc_handler *desc_handler; /*!< usb device descriptor handler pointer */ + + usb_ept_info ept_in[USB_EPT_MAX_NUM]; /*!< usb in endpoint infomation struct */ + usb_ept_info ept_out[USB_EPT_MAX_NUM]; /*!< usb out endpoint infomation struct */ + + usb_setup_type setup; /*!< usb setup type struct */ + uint8_t setup_buffer[12]; /*!< usb setup request buffer */ + + uint8_t ept0_sts; /*!< usb control endpoint 0 state */ + uint8_t speed; /*!< usb speed */ + uint16_t ept0_wlength; /*!< usb endpoint 0 transfer length */ + + usbd_conn_state conn_state; /*!< usb current connect state */ + usbd_conn_state old_conn_state; /*!< usb save the previous connect state */ + + uint8_t device_addr; /*!< device address */ + uint8_t remote_wakup; /*!< remote wakeup state */ + uint8_t default_config; /*!< usb default config state */ + uint8_t dev_config; /*!< usb device config state */ + uint32_t config_status; /*!< usb configure status */ +}usbd_core_type; + +void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_ctrl_unsupport(usbd_core_type *udev); +void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len); +void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len); +void usbd_ctrl_send_status(usbd_core_type *udev); +void usbd_ctrl_recv_status(usbd_core_type *udev); +void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr); +void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr); +void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket); +void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr); +void usbd_ept_send(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len); +void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len); +void usbd_connect(usbd_core_type *udev); +void usbd_disconnect(usbd_core_type *udev); +void usbd_set_device_addr(usbd_core_type *udev, uint8_t address); +uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr); +void usb_ept_defaut_init(usbd_core_type *udev); +usbd_conn_state usbd_connect_state_get(usbd_core_type *udev); +void usbd_remote_wakeup(usbd_core_type *udev); +void usbd_enter_suspend(usbd_core_type *udev); +void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num); +void usbd_fifo_alloc(usbd_core_type *udev); +usb_sts_type usbd_core_init(usbd_core_type *udev, + usb_reg_type *usb_reg, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler, + uint8_t core_id); +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h new file mode 100644 index 0000000000..9387340d74 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h @@ -0,0 +1,82 @@ +/** + ************************************************************************** + * @file usbd_int.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb interrupt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_INT_H +#define __USBD_INT_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_int + * @{ + */ + +/** @defgroup USBD_interrupt_exported_types + * @{ + */ +/* includes ------------------------------------------------------------------*/ +#include "usbd_core.h" +#include "usb_core.h" + +void usbd_irq_handler(otg_core_type *udev); +void usbd_ept_handler(usbd_core_type *udev); +void usbd_reset_handler(usbd_core_type *udev); +void usbd_sof_handler(usbd_core_type *udev); +void usbd_suspend_handler(usbd_core_type *udev); +void usbd_wakeup_handler(usbd_core_type *udev); +void usbd_inept_handler(usbd_core_type *udev); +void usbd_outept_handler(usbd_core_type *udev); +void usbd_enumdone_handler(usbd_core_type *udev); +void usbd_rxflvl_handler(usbd_core_type *udev); +void usbd_incomisioin_handler(usbd_core_type *udev); +void usbd_discon_handler(usbd_core_type *udev); +void usbd_incomisoout_handler(usbd_core_type *udev); +void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h new file mode 100644 index 0000000000..052f7d1a7b --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h @@ -0,0 +1,73 @@ +/** + ************************************************************************** + * @file usb_sdr.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_SDR_H +#define __USB_SDR_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" +#include "usb_core.h" +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_standard_request + * @{ + */ + +/** @defgroup USBD_sdr_exported_functions + * @{ + */ + + +void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf); +usb_sts_type usbd_device_request(usbd_core_type *udev); +usb_sts_type usbd_interface_request(usbd_core_type *udev); +usb_sts_type usbd_endpoint_request(usbd_core_type *udev); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h new file mode 100644 index 0000000000..10accd9743 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h @@ -0,0 +1,375 @@ +/** + ************************************************************************** + * @file usbh_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_CORE_H +#define __USBH_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_core + * @{ + */ + +/** @defgroup USBH_core_exported_types + * @{ + */ + + +#ifdef USE_OTG_HOST_MODE + +/** + * @brief usb channel flag + */ +typedef enum +{ + HCH_IDLE, /*!< usb host channel idle */ + HCH_XFRC, /*!< usb host channel transfer completed */ + HCH_HALTED, /*!< usb host channel halted */ + HCH_NAK, /*!< usb host channel nak */ + HCH_NYET, /*!< usb host channel nyet */ + HCH_STALL, /*!< usb host channel stall */ + HCH_XACTERR, /*!< usb host channel transaction error */ + HCH_BBLERR, /*!< usb host channel babble error */ + HCH_DATATGLERR /*!< usb host channel data toggle error */ +} hch_sts_type; + +/** + * @brief usb channel state + */ +typedef enum +{ + URB_IDLE = 0, /*!< usb request idle state */ + URB_DONE, /*!< usb request done state */ + URB_NOTREADY, /*!< usb request not ready state */ + URB_NYET, /*!< usb request nyet stat e*/ + URB_ERROR, /*!< usb request error state */ + URB_STALL /*!< usb request stall state */ +} urb_sts_type; + +/** + * @brief usb control channel flag + */ +typedef enum +{ + CTRL_START = 0, /*!< usb control request start */ + CTRL_XFERC, /*!< usb control request completed */ + CTRL_HALTED, /*!< usb control request halted */ + CTRL_NAK, /*!< usb control request nak */ + CTRL_STALL, /*!< usb control request stall */ + CTRL_XACTERR, /*!< usb control request transaction error */ + CTRL_BBLERR, /*!< usb control request babble error */ + CTRL_DATATGLERR, /*!< usb control request data toggle error */ + CTRL_FAIL /*!< usb control request failed */ +} ctrl_sts_type; + +/** + * @brief usb host control state machine + */ +typedef enum +{ + CONTROL_IDLE, /*!< usb control state idle */ + CONTROL_SETUP, /*!< usb control state setup */ + CONTROL_SETUP_WAIT, /*!< usb control state setup wait */ + CONTROL_DATA_IN, /*!< usb control state data in */ + CONTROL_DATA_IN_WAIT, /*!< usb control state data in wait */ + CONTROL_DATA_OUT, /*!< usb control state data out */ + CONTROL_DATA_OUT_WAIT, /*!< usb control state data out wait */ + CONTROL_STATUS_IN, /*!< usb control state status in */ + CONTROL_STATUS_IN_WAIT, /*!< usb control state status in wait */ + CONTROL_STATUS_OUT, /*!< usb control state out */ + CONTROL_STATUS_OUT_WAIT, /*!< usb control state out wait */ + CONTROL_ERROR, /*!< usb control state error */ + CONTROL_STALL, /*!< usb control state stall */ + CONTROL_COMPLETE /*!< usb control state complete */ +} ctrl_ept0_sts_type; + +/** + * @brief usb host enumration state machine + */ +typedef enum +{ + ENUM_IDLE, /*!< usb host enumration state idle */ + ENUM_GET_MIN_DESC, /*!< usb host enumration state get descriptor 8 byte*/ + ENUM_GET_FULL_DESC, /*!< usb host enumration state get descriptor 18 byte*/ + ENUM_SET_ADDR, /*!< usb host enumration state set address */ + ENUM_GET_CFG, /*!< usb host enumration state get configuration */ + ENUM_GET_FULL_CFG, /*!< usb host enumration state get full configuration */ + ENUM_GET_MFC_STRING, /*!< usb host enumration state get manufacturer string */ + ENUM_GET_PRODUCT_STRING, /*!< usb host enumration state get product string */ + ENUM_GET_SERIALNUM_STRING, /*!< usb host enumration state get serial number string */ + ENUM_SET_CONFIG, /*!< usb host enumration state set config */ + ENUM_COMPLETE, /*!< usb host enumration state complete */ +} usbh_enum_sts_type; + +/** + * @brief usb host global state machine + */ +typedef enum +{ + USBH_IDLE, /*!< usb host global state idle */ + USBH_PORT_EN, /*!< usb host global state port enable */ + USBH_ATTACHED, /*!< usb host global state attached */ + USBH_DISCONNECT, /*!< usb host global state disconnect */ + USBH_DEV_SPEED, /*!< usb host global state device speed */ + USBH_ENUMERATION, /*!< usb host global state enumeration */ + USBH_CLASS_REQUEST, /*!< usb host global state class request */ + USBH_CLASS, /*!< usb host global state class */ + USBH_CTRL_XFER, /*!< usb host global state control transfer */ + USBH_USER_HANDLER, /*!< usb host global state user handler */ + USBH_SUSPEND, /*!< usb host global state suspend */ + USBH_SUSPENDED, /*!< usb host have in suspend mode */ + USBH_WAKEUP, /*!< usb host global state wakeup */ + USBH_UNSUPPORT, /*!< usb host global unsupport device */ + USBH_ERROR_STATE, /*!< usb host global state error */ +} usbh_gstate_type; + +/** + * @brief usb host transfer state + */ +typedef enum +{ + CMD_IDLE, /*!< usb host transfer state idle */ + CMD_SEND, /*!< usb host transfer state send */ + CMD_WAIT /*!< usb host transfer state wait */ +} cmd_sts_type; + +/** + * @brief usb host channel malloc state + */ +#define HCH_OK 0x0000 /*!< usb channel malloc state ok */ +#define HCH_USED 0x8000 /*!< usb channel had used */ +#define HCH_ERROR 0xFFFF /*!< usb channel error */ +#define HCH_USED_MASK 0x7FFF /*!< usb channel use mask */ + +/** + * @brief channel pid + */ +#define HCH_PID_DATA0 0 /*!< usb channel pid data 0 */ +#define HCH_PID_DATA2 1 /*!< usb channel pid data 2 */ +#define HCH_PID_DATA1 2 /*!< usb channel pid data 1 */ +#define HCH_PID_SETUP 3 /*!< usb channel pid setup */ + +/** + * @brief channel data transfer direction + */ +#define USB_REQUEST_DIR_MASK 0x80 /*!< usb request direction mask */ +#define USB_DIR_H2D USB_REQ_DIR_HTD /*!< usb request direction host to device */ +#define USB_DIR_D2H USB_REQ_DIR_DTH /*!< usb request direction device to host */ + +/** + * @brief request timeout + */ +#define DATA_STAGE_TIMEOUT 5000 /*!< usb data stage timeout */ +#define NODATA_STAGE_TIMEOUT 50 /*!< usb no-data stage timeout */ + +/** + * @brief max interface and endpoint + */ +#define USBH_MAX_ERROR_COUNT 2 /*!< usb support maximum error */ +#define USBH_MAX_INTERFACE 5 /*!< usb support maximum interface */ +#define USBH_MAX_ENDPOINT 5 /*!< usb support maximum endpoint */ + +/** + * @brief interface descriptor + */ +typedef struct +{ + usb_interface_desc_type interface; /*!< usb device interface descriptor structure */ + usb_endpoint_desc_type endpoint[USBH_MAX_ENDPOINT]; /*!< usb device endpoint descriptor structure array */ +} usb_itf_desc_type; + +/** + * @brief configure descriptor + */ +typedef struct +{ + usb_configuration_desc_type cfg; /*!< usb device configuration descriptor structure */ + usb_itf_desc_type interface[USBH_MAX_INTERFACE]; /*!< usb device interface descriptor structure array*/ +} usb_cfg_desc_type; + +/** + * @brief device descriptor + */ +typedef struct +{ + uint8_t address; /*!< usb device address */ + uint8_t speed; /*!< usb device speed */ + usb_device_desc_type dev_desc; /*!< usb device descriptor */ + usb_cfg_desc_type cfg_desc; /*!< usb device configuration */ +} usbh_dev_desc_type; + +/** + * @brief usb host control struct type + */ +typedef struct +{ + uint8_t hch_in; /*!< in channel number */ + uint8_t hch_out; /*!< out channel number */ + uint8_t ept0_size; /*!< endpoint 0 size */ + uint8_t *buffer; /*!< endpoint 0 transfer buffer */ + usb_setup_type setup; /*!< control setup type */ + uint16_t len; /*!< transfer length */ + uint8_t err_cnt; /*!< error counter */ + uint32_t timer; /*!< transfer timer */ + ctrl_sts_type sts; /*!< control transfer status */ + ctrl_ept0_sts_type state; /*!< endpoint 0 state */ +} usbh_ctrl_type; + +/** + * @brief host class handler type + */ +typedef struct +{ + usb_sts_type (*init_handler)(void *uhost); /*!< usb host class init handler */ + usb_sts_type (*reset_handler)(void *uhost); /*!< usb host class reset handler */ + usb_sts_type (*request_handler)(void *uhost); /*!< usb host class request handler */ + usb_sts_type (*process_handler)(void *uhost); /*!< usb host class process handler */ + void *pdata; /*!< usb host class data */ +} usbh_class_handler_type; + +/** + * @brief host user handler type + */ +typedef struct +{ + usb_sts_type (*user_init)(void); /*!< usb host user init handler */ + usb_sts_type (*user_reset)(void); /*!< usb host user reset handler */ + usb_sts_type (*user_attached)(void); /*!< usb host user attached handler */ + usb_sts_type (*user_disconnect)(void); /*!< usb host user disconnect handler */ + usb_sts_type (*user_speed)(uint8_t speed); /*!< usb host user speed handler */ + usb_sts_type (*user_mfc_string)(void *); /*!< usb host user manufacturer string handler */ + usb_sts_type (*user_product_string)(void *); /*!< usb host user product string handler */ + usb_sts_type (*user_serial_string)(void *); /*!< usb host user serial handler */ + usb_sts_type (*user_enumeration_done)(void); /*!< usb host user enumeration done handler */ + usb_sts_type (*user_application)(void); /*!< usb host user application handler */ + usb_sts_type (*user_active_vbus)(void *uhost, confirm_state state); /*!< usb host user active vbus */ + usb_sts_type (*user_not_support)(void); /*!< usb host user not support handler */ +} usbh_user_handler_type; + +/** + * @brief host host core handler type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< usb register pointer */ + + uint8_t global_state; /*!< usb host global state machine */ + uint8_t enum_state; /*!< usb host enumeration state machine */ + uint8_t req_state; /*!< usb host request state machine */ + + usbh_dev_desc_type dev; /*!< usb device descriptor */ + usbh_ctrl_type ctrl; /*!< usb host control transfer struct */ + + usbh_class_handler_type *class_handler; /*!< usb host class handler pointer */ + usbh_user_handler_type *user_handler; /*!< usb host user handler pointer */ + + usb_hch_type hch[USB_HOST_CHANNEL_NUM]; /*!< usb host channel array */ + uint8_t rx_buffer[USB_MAX_DATA_LENGTH]; /*!< usb host rx buffer */ + + uint32_t conn_sts; /*!< connect status */ + uint32_t port_enable; /*!< port enable status */ + uint32_t timer; /*!< sof timer */ + + uint32_t err_cnt[USB_HOST_CHANNEL_NUM]; /*!< error counter */ + uint32_t xfer_cnt[USB_HOST_CHANNEL_NUM]; /*!< xfer counter */ + hch_sts_type hch_state[USB_HOST_CHANNEL_NUM];/*!< channel state */ + urb_sts_type urb_state[USB_HOST_CHANNEL_NUM];/*!< usb request state */ + uint16_t channel[USB_HOST_CHANNEL_NUM]; /*!< channel array */ +} usbh_core_type; + + +void usbh_free_channel(usbh_core_type *uhost, uint8_t index); +uint16_t usbh_get_free_channel(usbh_core_type *uhost); +usb_sts_type usbh_set_toggle(usbh_core_type *uhost, uint8_t hc_num, uint8_t toggle); +usb_sts_type usbh_in_out_request(usbh_core_type *uhost, uint8_t hc_num); +usb_sts_type usbh_interrupt_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_interrupt_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_bulk_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_bulk_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_isoc_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_isoc_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_cfg_default_init(usbh_core_type *uhost); +void usbh_enter_suspend(usbh_core_type *uhost); +void usbh_resume(usbh_core_type *uhost); + +uint16_t usbh_alloc_channel(usbh_core_type *uhost, uint8_t ept_addr); +urb_sts_type usbh_get_urb_status(usbh_core_type *uhost, uint8_t ch_num); +usb_sts_type usbh_ctrl_result_check(usbh_core_type *uhost, + ctrl_ept0_sts_type next_ctrl_state, + uint8_t next_enum_state); +uint8_t usbh_alloc_address(void); +void usbh_reset_port(usbh_core_type *uhost); +usb_sts_type usbh_loop_handler(usbh_core_type *uhost); +void usbh_ch_disable(usbh_core_type *uhost, uint8_t chn); +void usbh_hc_open(usbh_core_type *uhost, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed); +void usbh_active_vbus(usbh_core_type *uhost, confirm_state state); + +usb_sts_type usbh_core_init(usbh_core_type *uhost, + usb_reg_type *usb_reg, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler, + uint8_t core_id); +#endif + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h new file mode 100644 index 0000000000..c059e693e3 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h @@ -0,0 +1,109 @@ +/** + ************************************************************************** + * @file usbh_ctrl.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_CTRL_H +#define __USBH_CTRL_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" +#include "usbh_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_control + * @{ + */ + +/** @defgroup USBH_ctrl_exported_types + * @{ + */ + +usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num); +usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num); +usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num); +usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout); +usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length); +usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length, + uint8_t req_type, uint16_t wvalue, + uint8_t *buffer); +void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length); +usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len); +void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf); +void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf); +usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost, + uint8_t *buffer, uint16_t length); +uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol); +void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length); +usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length); +usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length); +usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config); +usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address); +usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting); +usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index); +usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index); +usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h new file mode 100644 index 0000000000..dcb2b31638 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h @@ -0,0 +1,77 @@ +/** + ************************************************************************** + * @file usbh_int.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_INT_H +#define __USBH_INT_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_int + * @{ + */ + +/** @defgroup USBH_interrupt_exported_types + * @{ + */ + +/* includes ------------------------------------------------------------------*/ +#include "usbh_core.h" +#include "usb_core.h" +void usbh_irq_handler(otg_core_type *hdev); +void usbh_hch_handler(usbh_core_type *uhost); +void usbh_port_handler(usbh_core_type *uhost); +void usbh_disconnect_handler(usbh_core_type *uhost); +void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn); +void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn); +void usbh_rx_qlvl_handler(usbh_core_type *uhost); +void usbh_wakeup_handler(usbh_core_type *uhost); +void usbh_sof_handler(usbh_core_type *uhost); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c new file mode 100644 index 0000000000..4fb5655217 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c @@ -0,0 +1,188 @@ +/** + ************************************************************************** + * @file usb_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usb_core.h" + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @defgroup USB_drivers_core + * @brief usb global drivers core + * @{ + */ + +/** @defgroup USB_core_private_functions + * @{ + */ + +usb_sts_type usb_core_config(otg_core_type *udev, uint8_t core_id); + +/** + * @brief usb core config + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @retval usb_sts_type + */ +usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id) +{ + /* set usb speed and core id */ + otgdev->cfg.speed = core_id; + otgdev->cfg.core_id = core_id; + + /* default sof out and vbus ignore */ + otgdev->cfg.sof_out = FALSE; + otgdev->cfg.vbusig = FALSE; + + /* set max size */ + otgdev->cfg.max_size = 64; + + /* set support number of channel and endpoint */ +#ifdef USE_OTG_HOST_MODE + otgdev->cfg.hc_num = USB_HOST_CHANNEL_NUM; +#endif +#ifdef USE_OTG_DEVICE_MODE + otgdev->cfg.ept_num = USB_EPT_MAX_NUM; +#endif + otgdev->cfg.fifo_size = OTG_FIFO_SIZE; + if(core_id == USB_FULL_SPEED_CORE_ID) + { + otgdev->cfg.phy_itface = 2; + } +#ifdef USB_SOF_OUTPUT_ENABLE + otgdev->cfg.sof_out = TRUE; +#endif + +#ifdef USB_VBUS_IGNORE + otgdev->cfg.vbusig = TRUE; +#endif + + return USB_OK; +} + +#ifdef USE_OTG_DEVICE_MODE +/** + * @brief usb device initialization + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @param usb_id: select use OTG1 or OTG2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @param dev_handler: usb class callback handler + * @param desc_handler: device config callback handler + * @retval usb_sts_type + */ +usb_sts_type usbd_init(otg_core_type *otgdev, + uint8_t core_id, uint8_t usb_id, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler) +{ + usb_sts_type usb_sts = USB_OK; + + /* select use OTG1 or OTG2 */ + otgdev->usb_reg = usb_global_select_core(usb_id); + + /* usb device core config */ + usb_core_config(otgdev, core_id); + + if(otgdev->cfg.sof_out) + { + otgdev->usb_reg->gccfg_bit.sofouten = TRUE; + } + + if(otgdev->cfg.vbusig) + { + otgdev->usb_reg->gccfg_bit.vbusig = TRUE; + } + + /* usb device core init */ + usbd_core_init(&(otgdev->dev), otgdev->usb_reg, + class_handler, + desc_handler, + core_id); + + return usb_sts; +} +#endif + +#ifdef USE_OTG_HOST_MODE + +/** + * @brief usb host initialization. + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @param usb_id: select use OTG1 or OTG2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @param class_handler: usb class callback handler + * @param user_handler: user callback handler + * @retval usb_sts_type + */ +usb_sts_type usbh_init(otg_core_type *otgdev, + uint8_t core_id, uint8_t usb_id, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler) +{ + usb_sts_type status = USB_OK; + + /* select use otg1 or otg2 */ + otgdev->usb_reg = usb_global_select_core(usb_id); + + /* usb core config */ + usb_core_config(otgdev, core_id); + + if(otgdev->cfg.sof_out) + { + otgdev->usb_reg->gccfg_bit.sofouten = TRUE; + } + + if(otgdev->cfg.vbusig) + { + otgdev->usb_reg->gccfg_bit.vbusig = TRUE; + } + + /* usb host core init */ + usbh_core_init(&otgdev->host, otgdev->usb_reg, + class_handler, + user_handler, + core_id); + + return status; +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c new file mode 100644 index 0000000000..b64914a78d --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c @@ -0,0 +1,884 @@ +/** + ************************************************************************** + * @file usbd_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb device driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "usb_core.h" +#include "usbd_core.h" +#include "usbd_sdr.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_core + * @brief usb device drivers core + * @{ + */ + +/** @defgroup USBD_core_private_functions + * @{ + */ + +/** + * @brief usb core in transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_addr) +{ + /* get endpoint info*/ + usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F]; + + if(ept_addr == 0) + { + if(udev->ept0_sts == USB_EPT0_DATA_IN) + { + if(ept_info->rem0_len > ept_info->maxpacket) + { + ept_info->rem0_len -= ept_info->maxpacket; + usbd_ept_send(udev, 0, ept_info->trans_buf, + MIN(ept_info->rem0_len, ept_info->maxpacket)); + } + /* endpoint 0 */ + else if(ept_info->last_len == ept_info->maxpacket + && ept_info->ept0_slen >= ept_info->maxpacket + && ept_info->ept0_slen < udev->ept0_wlength) + { + ept_info->last_len = 0; + usbd_ept_send(udev, 0, 0, 0); + usbd_ept_recv(udev, ept_addr, 0, 0); + } + else + { + + if(udev->class_handler->ept0_tx_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + udev->class_handler->ept0_tx_handler(udev); + } + usbd_ctrl_recv_status(udev); + + } + } + } + else if(udev->class_handler->in_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + /* other user define endpoint */ + udev->class_handler->in_handler(udev, ept_addr); + } +} + +/** + * @brief usb core out transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_addr) +{ + /* get endpoint info*/ + usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F]; + + if(ept_addr == 0) + { + /* endpoint 0 */ + if(udev->ept0_sts == USB_EPT0_DATA_OUT) + { + if(ept_info->rem0_len > ept_info->maxpacket) + { + ept_info->rem0_len -= ept_info->maxpacket; + usbd_ept_recv(udev, ept_addr, ept_info->trans_buf, + MIN(ept_info->rem0_len, ept_info->maxpacket)); + } + else + { + if(udev->class_handler->ept0_rx_handler != 0) + { + udev->class_handler->ept0_rx_handler(udev); + } + usbd_ctrl_send_status(udev); + } + } + } + else if(udev->class_handler->out_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + /* other user define endpoint */ + udev->class_handler->out_handler(udev, ept_addr); + } +} + +/** + * @brief usb core setup transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + /* setup parse */ + usbd_setup_request_parse(&udev->setup, udev->setup_buffer); + + /* set ept0 status */ + udev->ept0_sts = USB_EPT0_SETUP; + udev->ept0_wlength = udev->setup.wLength; + + switch(udev->setup.bmRequestType & USB_REQ_RECIPIENT_MASK) + { + case USB_REQ_RECIPIENT_DEVICE: + /* recipient device request */ + usbd_device_request(udev); + break; + case USB_REQ_RECIPIENT_INTERFACE: + /* recipient interface request */ + usbd_interface_request(udev); + break; + case USB_REQ_RECIPIENT_ENDPOINT: + /* recipient endpoint request */ + usbd_endpoint_request(udev); + break; + default: + break; + } +} + +/** + * @brief usb control endpoint send data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: send data buffer + * @param len: send data length + * @retval none + */ +void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len) +{ + usb_ept_info *ept_info = &udev->ept_in[0]; + + ept_info->ept0_slen = len; + ept_info->rem0_len = len; + udev->ept0_sts = USB_EPT0_DATA_IN; + + usbd_ept_send(udev, 0, buffer, len); +} + +/** + * @brief usb control endpoint recv data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: recv data buffer + * @param len: recv data length + * @retval none + */ +void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len) +{ + usb_ept_info *ept_info = &udev->ept_out[0]; + + ept_info->ept0_slen = len; + ept_info->rem0_len = len; + udev->ept0_sts = USB_EPT0_DATA_OUT; + + usbd_ept_recv(udev, 0, buffer, len); +} + +/** + * @brief usb control endpoint send in status + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_send_status(usbd_core_type *udev) +{ + udev->ept0_sts = USB_EPT0_STATUS_IN; + + usbd_ept_send(udev, 0, 0, 0); +} + +/** + * @brief usb control endpoint send out status + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_recv_status(usbd_core_type *udev) +{ + udev->ept0_sts = USB_EPT0_STATUS_OUT; + + usbd_ept_recv(udev, 0, 0, 0); +} + +/** + * @brief clear endpoint stall + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + usb_reg_type *usbx = udev->usb_reg; + + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + usb_ept_clear_stall(usbx, ept_info); + ept_info->stall = 0; +} + +/** + * @brief usb set endpoint to stall status + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + usb_reg_type *usbx = udev->usb_reg; + + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + usb_ept_stall(usbx, ept_info); + + ept_info->stall = 1; +} + +/** + * @brief un-support device request + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_unsupport(usbd_core_type *udev) +{ + /* return stall status */ + usbd_set_stall(udev, 0x00); + usbd_set_stall(udev, 0x80); +} + +/** + * @brief get endpoint receive data length + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval data receive len + */ +uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept = &udev->ept_out[ept_addr & 0x7F]; + return ept->trans_len; +} + +/** + * @brief usb open endpoint + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param ept_type: endpoint type + * @param maxpacket: endpoint support max buffer size + * @retval none + */ +void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket) +{ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info; + + if((ept_addr & 0x80) == 0) + { + /* out endpoint info */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + ept_info->inout = EPT_DIR_OUT; + } + else + { + /* in endpoint info */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + ept_info->inout = EPT_DIR_IN; + } + + /* set endpoint maxpacket and type */ + ept_info->maxpacket = maxpacket; + ept_info->trans_type = ept_type; + + /* open endpoint */ + usb_ept_open(usbx, ept_info); +} + +/** + * @brief usb close endpoint + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + + /* close endpoint */ + usb_ept_close(udev->usb_reg, ept_info); +} + +/** + * @brief usb device connect to host + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_connect(usbd_core_type *udev) +{ + usb_connect(udev->usb_reg); +} + +/** + * @brief usb device disconnect to host + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_disconnect(usbd_core_type *udev) +{ + usb_disconnect(udev->usb_reg); +} + +/** + * @brief usb device set device address. + * @param udev: to the structure of usbd_core_type + * @param address: host assignment address + * @retval none + */ +void usbd_set_device_addr(usbd_core_type *udev, uint8_t address) +{ + usb_set_address(udev->usb_reg, address); +} + +/** + * @brief usb endpoint structure initialization + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usb_ept_default_init(usbd_core_type *udev) +{ + uint8_t i_index = 0; + /* init in endpoint info structure */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + udev->ept_in[i_index].eptn = i_index; + udev->ept_in[i_index].ept_address = i_index; + udev->ept_in[i_index].inout = EPT_DIR_IN; + udev->ept_in[i_index].maxpacket = 0; + udev->ept_in[i_index].trans_buf = 0; + udev->ept_in[i_index].total_len = 0; + } + + /* init out endpoint info structure */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + udev->ept_out[i_index].eptn = i_index; + udev->ept_out[i_index].ept_address = i_index; + udev->ept_out[i_index].inout = EPT_DIR_OUT; + udev->ept_out[i_index].maxpacket = 0; + udev->ept_out[i_index].trans_buf = 0; + udev->ept_out[i_index].total_len = 0; + } +} + +/** + * @brief endpoint send data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: send data buffer + * @param len: send data length + * @retval none + */ +void usbd_ept_send(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len) +{ + /* get endpoint info struct and register */ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F]; + otg_eptin_type *ept_in = USB_INEPT(usbx, ept_info->eptn); + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t pktcnt; + + /* set send data buffer and length */ + ept_info->trans_buf = buffer; + ept_info->total_len = len; + ept_info->trans_len = 0; + + /* transfer data len is zero */ + if(ept_info->total_len == 0) + { + ept_in->dieptsiz_bit.pktcnt = 1; + ept_in->dieptsiz_bit.xfersize = 0; + } + else + { + if((ept_addr & 0x7F) == 0) // endpoint 0 + { + /* endpoint 0 */ + if(ept_info->total_len > ept_info->maxpacket) + { + ept_info->total_len = ept_info->maxpacket; + } + + /* set transfer size */ + ept_in->dieptsiz_bit.xfersize = ept_info->total_len; + + /* set packet count */ + ept_in->dieptsiz_bit.pktcnt = 1; + + ept_info->last_len = ept_info->total_len; + } + else + { + /* other endpoint */ + + /* packet count */ + pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket; + + /* set transfer size */ + ept_in->dieptsiz_bit.xfersize = ept_info->total_len; + + /* set packet count */ + ept_in->dieptsiz_bit.pktcnt = pktcnt; + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + ept_in->dieptsiz_bit.mc = 1; + } + } + } + + if(ept_info->trans_type != EPT_ISO_TYPE) + { + if(ept_info->total_len > 0) + { + /* set in endpoint tx fifo empty interrupt mask */ + dev->diepempmsk |= 1 << ept_info->eptn; + } + } + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + if((dev->dsts_bit.soffn & 0x1) == 0) + { + ept_in->diepctl_bit.setd1pid = TRUE; + } + else + { + ept_in->diepctl_bit.setd0pid = TRUE; + } + } + + /* clear endpoint nak */ + ept_in->diepctl_bit.cnak = TRUE; + + /* endpoint enable */ + ept_in->diepctl_bit.eptena = TRUE; + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + /* write data to fifo */ + usb_write_packet(usbx, ept_info->trans_buf, ept_info->eptn, ept_info->total_len); + } +} + +/** + * @brief endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: receive data buffer + * @param len: receive data length + * @retval none + */ +void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len) +{ + /* get endpoint info struct and register */ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F]; + otg_eptout_type *ept_out = USB_OUTEPT(usbx, ept_info->eptn); + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t pktcnt; + + /* set receive data buffer and length */ + ept_info->trans_buf = buffer; + ept_info->total_len = len; + ept_info->trans_len = 0; + + if((ept_addr & 0x7F) == 0) + { + /* endpoint 0 */ + ept_info->total_len = ept_info->maxpacket; + } + + if(ept_info->total_len == 0 || ((ept_addr & 0x7F) == 0)) + { + /* set transfer size */ + ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket; + + /* set packet count */ + ept_out->doeptsiz_bit.pktcnt = 1; + } + else + { + pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket; + + /* set transfer size */ + ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket * pktcnt; + + /* set packet count */ + ept_out->doeptsiz_bit.pktcnt = pktcnt; + } + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + if((dev->dsts_bit.soffn & 0x01) == 0) + { + ept_out->doepctl_bit.setd1pid = TRUE; + } + else + { + ept_out->doepctl_bit.setd0pid = TRUE; + } + } + + /* clear endpoint nak */ + ept_out->doepctl_bit.cnak = TRUE; + + /* endpoint enable */ + ept_out->doepctl_bit.eptena = TRUE; +} + +/** + * @brief get usb connect state + * @param udev: to the structure of usbd_core_type + * @retval usb connect state + */ +usbd_conn_state usbd_connect_state_get(usbd_core_type *udev) +{ + return udev->conn_state; +} + +/** + * @brief usb device remote wakeup + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_remote_wakeup(usbd_core_type *udev) +{ + /* check device is in suspend mode */ + if(usb_suspend_status_get(udev->usb_reg) == 1) + { + /* set connect state */ + udev->conn_state = udev->old_conn_state; + + /* open phy clock */ + usb_open_phy_clk(udev->usb_reg); + + /* set remote wakeup */ + usb_remote_wkup_set(udev->usb_reg); + + /* delay 10 ms */ + usb_delay_ms(10); + + /* clear remote wakup */ + usb_remote_wkup_clear(udev->usb_reg); + } +} + +/** + * @brief usb device enter suspend mode + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_enter_suspend(usbd_core_type *udev) +{ + /* check device is in suspend mode */ + if(usb_suspend_status_get(udev->usb_reg) == 1) + { + /* stop phy clk */ + usb_stop_phy_clk(udev->usb_reg); + } +} + +/** + * @brief usb device flush in endpoint fifo + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num) +{ + /* flush endpoint tx fifo */ + usb_flush_tx_fifo(udev->usb_reg, ept_num & 0x1F); +} + +/** + * @brief usb device endpoint fifo alloc + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_fifo_alloc(usbd_core_type *udev) +{ + usb_reg_type *usbx = udev->usb_reg; + + if(usbx == OTG1_GLOBAL) + { + /* set receive fifo size */ + usb_set_rx_fifo(usbx, USBD_RX_SIZE); + + /* set endpoint0 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT0, USBD_EP0_TX_SIZE); + + /* set endpoint1 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT1, USBD_EP1_TX_SIZE); + + /* set endpoint2 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT2, USBD_EP2_TX_SIZE); + + /* set endpoint3 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT3, USBD_EP3_TX_SIZE); + + if(USB_EPT_MAX_NUM == 8) + { + /* set endpoint4 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT4, USBD_EP4_TX_SIZE); + + /* set endpoint5 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT5, USBD_EP5_TX_SIZE); + + /* set endpoint6 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT6, USBD_EP6_TX_SIZE); + + /* set endpoint7 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT7, USBD_EP7_TX_SIZE); + } + } +#ifdef OTG2_GLOBAL + if(usbx == OTG2_GLOBAL) + { + /* set receive fifo size */ + usb_set_rx_fifo(usbx, USBD2_RX_SIZE); + + /* set endpoint0 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT0, USBD2_EP0_TX_SIZE); + + /* set endpoint1 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT1, USBD2_EP1_TX_SIZE); + + /* set endpoint2 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT2, USBD2_EP2_TX_SIZE); + + /* set endpoint3 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT3, USBD2_EP3_TX_SIZE); + + if(USB_EPT_MAX_NUM == 8) + { + /* set endpoint4 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT4, USBD2_EP4_TX_SIZE); + + /* set endpoint5 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT5, USBD2_EP5_TX_SIZE); + + /* set endpoint6 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT6, USBD2_EP6_TX_SIZE); + + /* set endpoint7 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT7, USBD2_EP7_TX_SIZE); + } + } +#endif +} + +/** + * @brief usb device core initialization + * @param udev: to the structure of usbd_core_type + * @param usb_reg: usb otgfs peripheral global register + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @param class_handler: usb class handler + * @param desc_handler: device config handler + * @param core_id: usb core id number + * @retval usb_sts_type + */ +usb_sts_type usbd_core_init(usbd_core_type *udev, + usb_reg_type *usb_reg, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler, + uint8_t core_id) +{ + UNUSED(core_id); + usb_reg_type *usbx; + otg_device_type *dev; + otg_eptin_type *ept_in; + otg_eptout_type *ept_out; + uint32_t i_index; + + udev->usb_reg = usb_reg; + usbx = usb_reg; + dev = OTG_DEVICE(usbx); + + /* set connect state */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* device class config */ + udev->device_addr = 0; + udev->class_handler = class_handler; + udev->desc_handler = desc_handler; + /* set device disconnect */ + usbd_disconnect(udev); + + /* set endpoint to default status */ + usb_ept_default_init(udev); + + /* disable usb global interrupt */ + usb_interrupt_disable(usbx); + + /* init global register */ + usb_global_init(usbx); + + /* set device mode */ + usb_global_set_mode(usbx, OTG_DEVICE_MODE); + + /* open phy clock */ + usb_open_phy_clk(udev->usb_reg); + + /* set periodic frame interval */ + dev->dcfg_bit.perfrint = DCFG_PERFRINT_80; + + /* set device speed to full-speed */ + dev->dcfg_bit.devspd = USB_DCFG_FULL_SPEED; + + /* flush all tx fifo */ + usb_flush_tx_fifo(usbx, 16); + + /* flush share rx fifo */ + usb_flush_rx_fifo(usbx); + + /* clear all endpoint interrupt flag and mask */ + dev->daint = 0xFFFFFFFF; + dev->daintmsk = 0; + dev->diepmsk = 0; + dev->doepmsk = 0; + + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + usbx->dieptxfn[i_index] = 0; + } + + /* endpoint fifo alloc */ + usbd_fifo_alloc(udev); + + /* disable all in endpoint */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + ept_in = USB_INEPT(usbx, i_index); + if(ept_in->diepctl_bit.eptena) + { + ept_in->diepctl = 0; + ept_in->diepctl_bit.eptdis = TRUE; + ept_in->diepctl_bit.snak = TRUE; + } + else + { + ept_in->diepctl = 0; + } + ept_in->dieptsiz = 0; + ept_in->diepint = 0xFF; + } + + /* disable all out endpoint */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + ept_out = USB_OUTEPT(usbx, i_index); + if(ept_out->doepctl_bit.eptena) + { + ept_out->doepctl = 0; + ept_out->doepctl_bit.eptdis = TRUE; + ept_out->doepctl_bit.snak = TRUE; + } + else + { + ept_out->doepctl = 0; + } + ept_out->doeptsiz = 0; + ept_out->doepint = 0xFF; + } + dev->diepmsk_bit.txfifoudrmsk = TRUE; + + /* clear global interrupt and mask */ + usbx->gintmsk = 0; + usbx->gintsts = 0xBFFFFFFF; + + /* enable global interrupt mask */ + usbx->gintmsk = USB_OTG_SOF_INT | USB_OTG_RXFLVL_INT | + USB_OTG_USBSUSP_INT | USB_OTG_USBRST_INT | + USB_OTG_ENUMDONE_INT | USB_OTG_IEPT_INT | + USB_OTG_OEPT_INT | USB_OTG_INCOMISOIN_INT | + USB_OTG_INCOMPIP_INCOMPISOOUT_INT | USB_OTG_WKUP_INT | + USB_OTG_OTGINT_INT; + + /* usb connect */ + usbd_connect(udev); + + /* enable global interrupt */ + usb_interrupt_enable(usbx); + + return USB_OK; + +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c new file mode 100644 index 0000000000..fdb19c368c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c @@ -0,0 +1,538 @@ +/** + ************************************************************************** + * @file usbd_int.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb interrupt request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_int.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_interrupt + * @brief usb device interrupt + * @{ + */ + +/** @defgroup USBD_int_private_functions + * @{ + */ + +/** + * @brief usb device interrput request handler. + * @param otgdev: to the structure of otg_core_type + * @retval none + */ +void usbd_irq_handler(otg_core_type *otgdev) +{ + otg_global_type *usbx = otgdev->usb_reg; + usbd_core_type *udev = &otgdev->dev; + uint32_t intsts = usb_global_get_all_interrupt(usbx); + + /* check current device mode */ + if(usbx->gintsts_bit.curmode == 0) + { + /* mode mismatch interrupt */ + if(intsts & USB_OTG_MODEMIS_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG); + } + + /* in endpoint interrupt */ + if(intsts & USB_OTG_IEPT_FLAG) + { + usbd_inept_handler(udev); + } + + /* out endpoint interrupt */ + if(intsts & USB_OTG_OEPT_FLAG) + { + usbd_outept_handler(udev); + } + + /* usb reset interrupt */ + if(intsts & USB_OTG_USBRST_FLAG) + { + usbd_reset_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_USBRST_FLAG); + } + + /* sof interrupt */ + if(intsts & USB_OTG_SOF_FLAG) + { + usbd_sof_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG); + } + + /* enumeration done interrupt */ + if(intsts & USB_OTG_ENUMDONE_FLAG) + { + usbd_enumdone_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_ENUMDONE_FLAG); + } + + /* rx non-empty interrupt, indicates that there is at least one + data packet pending to be read in rx fifo */ + if(intsts & USB_OTG_RXFLVL_FLAG) + { + usbd_rxflvl_handler(udev); + } + + /* incomplete isochronous in transfer interrupt */ + if(intsts & USB_OTG_INCOMISOIN_FLAG) + { + usbd_incomisioin_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG); + } + #ifndef USB_VBUS_IGNORE + /* disconnect detected interrupt */ + if(intsts & USB_OTG_OTGINT_FLAG) + { + uint32_t tmp = udev->usb_reg->gotgint; + if(udev->usb_reg->gotgint_bit.sesenddet) + usbd_discon_handler(udev); + udev->usb_reg->gotgint = tmp; + usb_global_clear_interrupt(usbx, USB_OTG_OTGINT_FLAG); + } +#endif + /* incomplete isochronous out transfer interrupt */ + if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG) + { + usbd_incomisoout_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG); + } + + /* resume/remote wakeup interrupt */ + if(intsts & USB_OTG_WKUP_FLAG) + { + usbd_wakeup_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG); + } + + /* usb suspend interrupt */ + if(intsts & USB_OTG_USBSUSP_FLAG) + { + usbd_suspend_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_USBSUSP_FLAG); + } + } +} + +/** + * @brief usb write tx fifo. + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num) +{ + otg_global_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_in[ept_num]; + uint32_t length = ept_info->total_len - ept_info->trans_len; + uint32_t wlen = 0; + + if(length > ept_info->maxpacket) + { + length = ept_info->maxpacket; + } + wlen = (length + 3) / 4; + + while((USB_INEPT(usbx, ept_num)->dtxfsts & USB_OTG_DTXFSTS_INEPTFSAV) > wlen && + (ept_info->trans_len < ept_info->total_len) && (ept_info->total_len != 0)) + { + length = ept_info->total_len - ept_info->trans_len; + if(length > ept_info->maxpacket) + { + length = ept_info->maxpacket; + } + wlen = (length + 3) / 4; + usb_write_packet(usbx, ept_info->trans_buf, ept_num, length); + + ept_info->trans_buf += length; + ept_info->trans_len += length; + + } + if(length <= 0) + { + OTG_DEVICE(usbx)->diepempmsk &= ~(0x1 << ept_num); + } +} + + +/** + * @brief usb in endpoint handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_inept_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t ept_num = 0, ept_int; + uint32_t intsts; + + /*get all endpoint interrut */ + intsts = usb_get_all_in_interrupt(usbx); + while(intsts) + { + if(intsts & 0x1) + { + /* get endpoint interrupt flag */ + ept_int = usb_ept_in_interrupt(usbx, ept_num); + + /* transfer completed interrupt */ + if(ept_int & USB_OTG_DIEPINT_XFERC_FLAG) + { + OTG_DEVICE(usbx)->diepempmsk &= ~(1 << ept_num); + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_XFERC_FLAG); + usbd_core_in_handler(udev, ept_num); + } + + /* timeout condition interrupt */ + if(ept_int & USB_OTG_DIEPINT_TIMEOUT_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_TIMEOUT_FLAG); + } + + /* in token received when tx fifo is empty */ + if(ept_int & USB_OTG_DIEPINT_INTKNTXFEMP_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INTKNTXFEMP_FLAG); + } + + /* in endpoint nak effective */ + if(ept_int & USB_OTG_DIEPINT_INEPTNAK_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INEPTNAK_FLAG); + } + + /* endpoint disable interrupt */ + if(ept_int & USB_OTG_DIEPINT_EPTDISD_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_EPTDISD_FLAG); + } + + /* transmit fifo empty interrupt */ + if(ept_int & USB_OTG_DIEPINT_TXFEMP_FLAG) + { + usb_write_empty_txfifo(udev, ept_num); + } + } + ept_num ++; + intsts >>= 1; + } +} + +/** + * @brief usb out endpoint handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_outept_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t ept_num = 0, ept_int; + uint32_t intsts; + + /* get all out endpoint interrupt */ + intsts = usb_get_all_out_interrupt(usbx); + + while(intsts) + { + if(intsts & 0x1) + { + /* get out endpoint interrupt */ + ept_int = usb_ept_out_interrupt(usbx, ept_num); + + /* transfer completed interrupt */ + if(ept_int & USB_OTG_DOEPINT_XFERC_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_XFERC_FLAG); + usbd_core_out_handler(udev, ept_num); + } + + /* setup phase done interrupt */ + if(ept_int & USB_OTG_DOEPINT_SETUP_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_SETUP_FLAG); + usbd_core_setup_handler(udev, ept_num); + if(udev->device_addr != 0) + { + OTG_DEVICE(udev->usb_reg)->dcfg_bit.devaddr = udev->device_addr; + udev->device_addr = 0; + } + } + + /* endpoint disable interrupt */ + if(ept_int & USB_OTG_DOEPINT_OUTTEPD_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_OUTTEPD_FLAG); + } + } + ept_num ++; + intsts >>= 1; + } +} + +/** + * @brief usb enumeration done handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_enumdone_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + usb_ept0_setup(usbx); + + usbx->gusbcfg_bit.usbtrdtim = USB_TRDTIM_16; + + /* open endpoint 0 out */ + usbd_ept_open(udev, 0x00, EPT_CONTROL_TYPE, 0x40); + + /* open endpoint 0 in */ + usbd_ept_open(udev, 0x80, EPT_CONTROL_TYPE, 0x40); + + /* usb connect state set to default */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* clear callback */ + if(udev->class_handler->clear_handler != 0) + udev->class_handler->clear_handler(udev); +} + +/** + * @brief usb rx non-empty handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_rxflvl_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t stsp; + uint32_t count; + uint32_t pktsts; + usb_ept_info *ept_info; + + /* disable rxflvl interrupt */ + usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, FALSE); + + /* get rx status */ + stsp = usbx->grxstsp; + + /*get the byte count of receive */ + count = (stsp & USB_OTG_GRXSTSP_BCNT) >> 4; + + /* get packet status */ + pktsts = (stsp &USB_OTG_GRXSTSP_PKTSTS) >> 17; + + /* get endpoint infomation struct */ + ept_info = &udev->ept_out[stsp & USB_OTG_GRXSTSP_EPTNUM]; + + /* received out data packet */ + if(pktsts == USB_OUT_STS_DATA) + { + if(count != 0) + { + /* read packet to buffer */ + usb_read_packet(usbx, ept_info->trans_buf, (stsp & USB_OTG_GRXSTSP_EPTNUM), count); + ept_info->trans_buf += count; + ept_info->trans_len += count; + + } + } + /* setup data received */ + else if ( pktsts == USB_SETUP_STS_DATA) + { + /* read packet to buffer */ + usb_read_packet(usbx, udev->setup_buffer, (stsp & USB_OTG_GRXSTSP_EPTNUM), count); + ept_info->trans_len += count; + } + + /* enable rxflvl interrupt */ + usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, TRUE); + +} + +/** + * @brief usb disconnect handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_discon_handler(usbd_core_type *udev) +{ + /* disconnect callback handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_DISCONNECT_EVNET); +} + + +/** + * @brief usb incomplete out handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_incomisoout_handler(usbd_core_type *udev) +{ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_OUTISOINCOM_EVENT); +} + +/** + * @brief usb incomplete in handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_incomisioin_handler(usbd_core_type *udev) +{ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_INISOINCOM_EVENT); +} + +/** + * @brief usb device reset interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_reset_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t i_index = 0; + + /* disable remote wakeup singal */ + dev->dctl_bit.rwkupsig = FALSE; + + /* endpoint fifo alloc */ + usbd_fifo_alloc(udev); + + /* flush all tx fifo */ + usb_flush_tx_fifo(usbx, 0x10); + + /* clear in and out endpoint interrupt flag */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + USB_INEPT(usbx, i_index)->diepint = 0xFF; + USB_OUTEPT(usbx, i_index)->doepint = 0xFF; + } + + /* clear endpoint flag */ + dev->daint = 0xFFFFFFFF; + + /*clear endpoint interrupt mask */ + dev->daintmsk = 0x10001; + + /* enable out endpoint xfer, eptdis, setup interrupt mask */ + dev->doepmsk_bit.xfercmsk = TRUE; + dev->doepmsk_bit.eptdismsk = TRUE; + dev->doepmsk_bit.setupmsk = TRUE; + + /* enable in endpoint xfer, eptdis, timeout interrupt mask */ + dev->diepmsk_bit.xfercmsk = TRUE; + dev->diepmsk_bit.eptdismsk = TRUE; + dev->diepmsk_bit.timeoutmsk = TRUE; + + /* set device address to 0 */ + usb_set_address(usbx, 0); + + /* enable endpoint 0 */ + usb_ept0_start(usbx); + + /* usb connect state set to default */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* user define reset event */ + if(udev->class_handler->event_handler) + udev->class_handler->event_handler(udev, USBD_RESET_EVENT); +} + +/** + * @brief usb device sof interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_sof_handler(usbd_core_type *udev) +{ + /* user sof handler in class define */ + if(udev->class_handler->sof_handler) + udev->class_handler->sof_handler(udev); +} + +/** + * @brief usb device suspend interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_suspend_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + if(OTG_DEVICE(usbx)->dsts_bit.suspsts) + { + /* save connect state */ + udev->old_conn_state = udev->conn_state; + + /* set current state to suspend */ + udev->conn_state = USB_CONN_STATE_SUSPENDED; + + /* enter suspend mode */ + usbd_enter_suspend(udev); + + /* user suspend handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_SUSPEND_EVENT); + } +} + +/** + * @brief usb device wakup interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_wakeup_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + /* clear remote wakeup bit */ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE; + + /* exit suspend mode */ + usb_open_phy_clk(udev->usb_reg); + + /* restore connect state */ + udev->conn_state = udev->old_conn_state; + + /* user suspend handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_WAKEUP_EVENT); +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c new file mode 100644 index 0000000000..6191044974 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c @@ -0,0 +1,535 @@ +/** + ************************************************************************** + * @file usbd_sdr.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb standard device request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_sdr.h" +#include + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_standard_request + * @brief usb device standard_request + * @{ + */ + +/** @defgroup USBD_sdr_private_functions + * @{ + */ + +static usb_sts_type usbd_get_descriptor(usbd_core_type *udev); +static usb_sts_type usbd_set_address(usbd_core_type *udev); +static usb_sts_type usbd_get_status(usbd_core_type *udev); +static usb_sts_type usbd_clear_feature(usbd_core_type *udev); +static usb_sts_type usbd_set_feature(usbd_core_type *udev); +static usb_sts_type usbd_get_configuration(usbd_core_type *udev); +static usb_sts_type usbd_set_configuration(usbd_core_type *udev); + +/** + * @brief usb parse standard setup request + * @param setup: setup structure + * @param buf: setup buffer + * @retval none + */ +void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf) +{ + setup->bmRequestType = *(uint8_t *) buf; + setup->bRequest = *(uint8_t *) (buf + 1); + setup->wValue = SWAPBYTE(buf + 2); + setup->wIndex = SWAPBYTE(buf + 4); + setup->wLength = SWAPBYTE(buf + 6); +} + +/** + * @brief get usb standard device description request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_descriptor(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + uint16_t len = 0; + usbd_desc_t *desc = NULL; + uint8_t desc_type = udev->setup.wValue >> 8; + switch(desc_type) + { + case USB_DESCIPTOR_TYPE_DEVICE: + desc = udev->desc_handler->get_device_descriptor(); + break; + case USB_DESCIPTOR_TYPE_CONFIGURATION: + desc = udev->desc_handler->get_device_configuration(); + break; + case USB_DESCIPTOR_TYPE_STRING: + { + uint8_t str_desc = (uint8_t)udev->setup.wValue; + switch(str_desc) + { + case USB_LANGID_STRING: + desc = udev->desc_handler->get_device_lang_id(); + break; + case USB_MFC_STRING: + desc = udev->desc_handler->get_device_manufacturer_string(); + break; + case USB_PRODUCT_STRING: + desc = udev->desc_handler->get_device_product_string(); + break; + case USB_SERIAL_STRING: + desc = udev->desc_handler->get_device_serial_string(); + break; + case USB_CONFIG_STRING: + desc = udev->desc_handler->get_device_config_string(); + break; + case USB_INTERFACE_STRING: + desc = udev->desc_handler->get_device_interface_string(); + break; + default: + udev->class_handler->setup_handler(udev, &udev->setup); + return ret; + } + break; + } + case USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER: + usbd_ctrl_unsupport(udev); + break; + case USB_DESCIPTOR_TYPE_OTHER_SPEED: + usbd_ctrl_unsupport(udev); + return ret; + default: + usbd_ctrl_unsupport(udev); + return ret; + } + + if(desc != NULL) + { + if((desc->length != 0) && (udev->setup.wLength != 0)) + { + len = MIN(desc->length , udev->setup.wLength); + usbd_ctrl_send(udev, desc->descriptor, len); + } + } + return ret; +} + +/** + * @brief this request sets the device address + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_address(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + uint8_t dev_addr; + + /* if wIndex or wLength are non-zero, then the behavior of + the device is not specified + */ + if(setup->wIndex == 0 && setup->wLength == 0) + { + dev_addr = (uint8_t)(setup->wValue) & 0x7f; + + /* device behavior when this request is received + while the device is in the configured state is not specified.*/ + if(udev->conn_state == USB_CONN_STATE_CONFIGURED ) + { + usbd_ctrl_unsupport(udev); + } + else + { + udev->device_addr = dev_addr; + + if(dev_addr != 0) + { + udev->conn_state = USB_CONN_STATE_ADDRESSED; + } + else + { + udev->conn_state = USB_CONN_STATE_DEFAULT; + } + usbd_ctrl_send_status(udev); + } + } + else + { + usbd_ctrl_unsupport(udev); + } + return ret; +} + +/** + * @brief get usb status request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_status(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + case USB_CONN_STATE_CONFIGURED: + if(udev->remote_wakup) + { + udev->config_status |= USB_CONF_REMOTE_WAKEUP; + } + usbd_ctrl_send(udev, (uint8_t *)(&udev->config_status), 2); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief clear usb feature request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_clear_feature(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + udev->remote_wakup = 0; + udev->config_status &= ~USB_CONF_REMOTE_WAKEUP; + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief set usb feature request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_feature(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + udev->remote_wakup = 1; + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + } + return ret; +} + +/** + * @brief get usb configuration request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_configuration(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if(setup->wLength != 1) + { + usbd_ctrl_unsupport(udev); + } + else + { + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + udev->default_config = 0; + usbd_ctrl_send(udev, (uint8_t *)(&udev->default_config), 1); + break; + case USB_CONN_STATE_CONFIGURED: + usbd_ctrl_send(udev, (uint8_t *)(&udev->dev_config), 1); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + } + return ret; +} + +/** + * @brief sets the usb device configuration request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_configuration(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + static uint8_t config_value; + usb_setup_type *setup = &udev->setup; + config_value = (uint8_t)setup->wValue; + + if(setup->wIndex == 0 && setup->wLength == 0) + { + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if(config_value) + { + udev->dev_config = config_value; + udev->conn_state = USB_CONN_STATE_CONFIGURED; + udev->class_handler->init_handler(udev); + usbd_ctrl_send_status(udev); + } + else + { + usbd_ctrl_send_status(udev); + } + + break; + case USB_CONN_STATE_CONFIGURED: + if(config_value == 0) + { + udev->conn_state = USB_CONN_STATE_ADDRESSED; + udev->dev_config = config_value; + udev->class_handler->clear_handler(udev); + usbd_ctrl_send_status(udev); + } + else if(config_value == udev->dev_config) + { + udev->class_handler->clear_handler(udev); + udev->dev_config = config_value; + udev->class_handler->init_handler(udev); + usbd_ctrl_send_status(udev); + } + else + { + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + } + else + { + usbd_ctrl_unsupport(udev); + } + return ret; +} + +/** + * @brief standard usb device requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_device_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) != USB_REQ_TYPE_STANDARD) + { + udev->class_handler->setup_handler(udev, &udev->setup); + return ret; + } + switch(udev->setup.bRequest) + { + case USB_STD_REQ_GET_STATUS: + usbd_get_status(udev); + break; + case USB_STD_REQ_CLEAR_FEATURE: + usbd_clear_feature(udev); + break; + case USB_STD_REQ_SET_FEATURE: + usbd_set_feature(udev); + break; + case USB_STD_REQ_SET_ADDRESS: + usbd_set_address(udev); + break; + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_get_descriptor(udev); + break; + case USB_STD_REQ_GET_CONFIGURATION: + usbd_get_configuration(udev); + break; + case USB_STD_REQ_SET_CONFIGURATION: + usbd_set_configuration(udev); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief standard usb interface requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_interface_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + switch(udev->conn_state) + { + case USB_CONN_STATE_CONFIGURED: + udev->class_handler->setup_handler(udev, &udev->setup); + if(setup->wLength == 0) + { + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief standard usb endpoint requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_endpoint_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + uint8_t ept_addr = LBYTE(setup->wIndex); + usb_ept_info *ept_info; + + if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) == USB_REQ_TYPE_CLASS) + { + udev->class_handler->setup_handler(udev, &udev->setup); + } + switch(setup->bRequest) + { + case USB_STD_REQ_GET_STATUS: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr & 0x7F) != 0) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + { + if((ept_addr & 0x80) != 0) + { + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + if(ept_info->stall == 1) + { + ept_info->status = 0x0001; + } + else + { + ept_info->status = 0x0000; + } + usbd_ctrl_send(udev, (uint8_t *)(&ept_info->status), 2); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + case USB_STD_REQ_CLEAR_FEATURE: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_EPT_HALT) + { + if((ept_addr & 0x7F) != 0x00 ) + { + usbd_clear_stall(udev, ept_addr); + udev->class_handler->setup_handler(udev, &udev->setup); + } + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + case USB_STD_REQ_SET_FEATURE: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_EPT_HALT) + { + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + } + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c new file mode 100644 index 0000000000..37ae05d014 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c @@ -0,0 +1,1241 @@ +/** + ************************************************************************** + * @file usbh_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_core.h" +#include "usb_core.h" +#include "usbh_ctrl.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_core + * @brief usb host drivers core + * @{ + */ + +/** @defgroup USBH_core_private_functions + * @{ + */ + +static void usbh_attached(usbh_core_type *uhost); +static void usbh_enumeration(usbh_core_type *uhost); +static void usbh_class_request(usbh_core_type *uhost); +static void usbh_class(usbh_core_type *uhost); +static void usbh_suspend(usbh_core_type *uhost); +static void usbh_wakeup(usbh_core_type *uhost); +static void usbh_disconnect(usbh_core_type *uhost); +/** + * @brief usb host free channel + * @param uhost: to the structure of usbh_core_type + * @param index: channle number + * @retval none + */ +void usbh_free_channel(usbh_core_type *uhost, uint8_t index) +{ + if(index < USB_HOST_CHANNEL_NUM) + { + /* free host channel */ + uhost->channel[index] = 0x0; + } +} + +/** + * @brief get usb host free channel + * @param uhost: to the structure of usbh_core_type + * @retval channel index + */ +uint16_t usbh_get_free_channel(usbh_core_type *uhost) +{ + uint16_t i_index = 0; + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + /* find unuse channel */ + if((uhost->channel[i_index] & HCH_USED) == 0) + { + /* return channel index */ + return i_index; + } + } + return HCH_ERROR; +} + + +/** + * @brief usb host set toggle + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param toggle: toggle value + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_toggle(usbh_core_type *uhost, uint8_t hc_num, uint8_t toggle) +{ + if(uhost->hch[hc_num].dir) + { + /* direction in */ + uhost->hch[hc_num].toggle_in = toggle; + } + else + { + /* direction out */ + uhost->hch[hc_num].toggle_out = toggle; + } + return USB_OK; +} + +/** + * @brief usb host in out request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_in_out_request(usbh_core_type *uhost, uint8_t hc_num) +{ + usb_sts_type status = USB_OK; + uint32_t n_packet = 0; + uint32_t num_words = 0; + uint32_t tmp; + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *ch = USB_CHL(uhost->usb_reg, hc_num); + + /* set usb request block to idle */ + uhost->urb_state[hc_num] = URB_IDLE; + uhost->hch[hc_num].state = HCH_IDLE; + + /* set usb channel transmit count to zero */ + uhost->hch[hc_num].trans_count = 0; + + /* check transmit data len */ + if(uhost->hch[hc_num].trans_len > 0) + { + /* count how many packet need to send */ + n_packet = (uhost->hch[hc_num].trans_len + \ + uhost->hch[hc_num].maxpacket - 1) / \ + uhost->hch[hc_num].maxpacket; + + /* packet count max 256 */ + if(n_packet > 256) + { + n_packet = 256; + uhost->hch[hc_num].trans_len = n_packet * uhost->hch[hc_num].maxpacket; + } + } + else + { + /* zero data len */ + n_packet = 1; + } + + /* direction is in */ + if(uhost->hch[hc_num].dir) + { + uhost->hch[hc_num].trans_len = n_packet * uhost->hch[hc_num].maxpacket; + } + + /* set transfer information to channel register */ + ch->hctsiz = (uhost->hch[hc_num].trans_len & USB_OTG_HCTSIZ_XFERSIZE) | + ((n_packet << 19) & USB_OTG_HCTSIZ_PKTCNT) | + ((uhost->hch[hc_num].data_pid << 29) & USB_OTG_HCTSIZ_PID); + + /* set odd frame */ + ch->hcchar_bit.oddfrm = !(OTG_HOST(uhost->usb_reg)->hfnum & 0x1); + + /* clear channel disable bit and enable channel */ + tmp = ch->hcchar; + tmp &= ~(USB_OTG_HCCHAR_CHDIS); + tmp |= USB_OTG_HCCHAR_CHENA; + ch->hcchar = tmp; + + /* channel direction is out and transfer len > 0 */ + if((uhost->hch[hc_num].dir == 0) && + (uhost->hch[hc_num].trans_len > 0 )) + { + switch(uhost->hch[hc_num].ept_type) + { + case EPT_CONTROL_TYPE: + case EPT_BULK_TYPE: + num_words = (uhost->hch[hc_num].trans_len + 3) / 4; + + /* non-periodic transfer */ + if(num_words > usbx->gnptxsts_bit.nptxfspcavail) + { + usbx->gintmsk_bit.nptxfempmsk = 1; + } + break; + case EPT_ISO_TYPE: + case EPT_INT_TYPE: + num_words = (uhost->hch[hc_num].trans_len + 3) / 4; + + /* periodic transfer */ + if(num_words > OTG_HOST(usbx)->hptxsts_bit.ptxfspcavil) + { + usbx->gintmsk_bit.ptxfempmsk = 1; + } + break; + default: + break; + } + /* write data to fifo */ + usb_write_packet(usbx, uhost->hch[hc_num].trans_buf, + hc_num, uhost->hch[hc_num].trans_len); + } + + return status; +} + +/** + * @brief usb host interrupt receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_interrupt_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_in == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host interrupt send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: send buffer + * @param length: send length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_interrupt_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_out == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host bulk receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_bulk_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_in == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host bulk send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_bulk_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_out == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host iso send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: send buffer + * @param length: send length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_isoc_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host iso receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_isoc_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host cfg default init + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_cfg_default_init(usbh_core_type *uhost) +{ + /* set global state to idle */ + uhost->global_state = USBH_IDLE; + + /* enumeration state to get description */ + uhost->enum_state = ENUM_GET_MIN_DESC; + + /* request state send */ + uhost->req_state = CMD_SEND; + + /* control transfer state is idle*/ + uhost->ctrl.state = CONTROL_IDLE; + + /* defaut endpoint 0 max size is 8byte */ + uhost->ctrl.ept0_size = 8; + + /* default device address is 0 */ + uhost->dev.address = 0; + + /* default speed is full speed */ + uhost->dev.speed = USB_FULL_SPEED_CORE_ID; + + uhost->timer = 0; + + uhost->ctrl.err_cnt = 0; + + /* free all channel */ + usbh_free_channel(uhost, uhost->ctrl.hch_in); + usbh_free_channel(uhost, uhost->ctrl.hch_out); + return USB_OK; +} + +/** + * @brief usb host enter suspend + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_enter_suspend(usbh_core_type *uhost) +{ + otg_host_type *host = OTG_HOST(uhost->usb_reg); + uint32_t hprt_val = host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + /* set port suspend */ + host->hprt = hprt_val | USB_OTG_HPRT_PRTSUSP; + + /* stop phy clock */ + usb_stop_phy_clk(uhost->usb_reg); + +} + +/** + * @brief usb host resume + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_resume(usbh_core_type *uhost) +{ + otg_host_type *host = OTG_HOST(uhost->usb_reg); + uint32_t temp = host->hprt; + + /* open phy clock */ + usb_open_phy_clk(uhost->usb_reg); + + /* clear port suspend and set port resume*/ + temp &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET + | USB_OTG_HPRT_PRTSUSP); + host->hprt = temp | USB_OTG_HPRT_PRTRES; + + /* delay 20 ms */ + usb_delay_ms(20); + + /*clear port resume */ + temp = host->hprt; + temp &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET + | USB_OTG_HPRT_PRTRES); + host->hprt = temp; + usb_delay_ms(5); +} + +/** + * @brief usb host core initialize + * @param uhost: to the structure of usbh_core_type + * @param usb_reg: usb otgfs peripheral global register + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @param class_handler: usb host class handler type pointer + * @param user_handler: usb host user handler type pointer + * @param core_id: usb core select id + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_core_init(usbh_core_type *uhost, + usb_reg_type *usb_reg, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler, + uint8_t core_id) +{ + usb_sts_type status = USB_OK; + uint32_t i_index; + otg_global_type *usbx = usb_reg; + otg_host_type *host = OTG_HOST(usbx); + uhost->usb_reg = usb_reg; + + /* host class handler */ + uhost->class_handler = class_handler; + uhost->user_handler = user_handler; + + /* host user handler */ + uhost->user_handler->user_init(); + + uhost->timer = 0; + + /* usb host cfg default init */ + usbh_cfg_default_init(uhost); + + /* clear host config to default value */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + uhost->err_cnt[i_index] = 0; + uhost->xfer_cnt[i_index] = 0; + uhost->hch_state[i_index] = HCH_IDLE; + uhost->hch[0].maxpacket = 8; + } + + /* no device connect */ + uhost->conn_sts = 0; + + /* disable usb interrupt */ + usb_interrupt_disable(usbx); + + /* usb global init */ + usb_global_init(usbx); + + /* set usb host mode */ + usb_global_set_mode(usbx, OTG_HOST_MODE); + + /* open usb phy clock*/ + usb_open_phy_clk(usbx); + + /* clock select */ + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); + + /* set support ls and fs device */ + host->hcfg_bit.fslssupp = 0; + + if(usbx == OTG1_GLOBAL) + { + /* set receive fifo size */ + usbx->grxfsiz = USBH_RX_FIFO_SIZE; + + /* set non-periodic transmit fifo start address and depth */ + usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH_RX_FIFO_SIZE; + usbx->gnptxfsiz_ept0tx_bit.nptxfdep = USBH_NP_TX_FIFO_SIZE; + + /* set periodic transmit fifo start address and depth */ + usbx->hptxfsiz_bit.ptxfstaddr = USBH_RX_FIFO_SIZE + USBH_NP_TX_FIFO_SIZE; + usbx->hptxfsiz_bit.ptxfsize = USBH_P_TX_FIFO_SIZE; + } +#ifdef OTG2_GLOBAL + if(usbx == OTG2_GLOBAL) + { + /* set receive fifo size */ + usbx->grxfsiz = USBH2_RX_FIFO_SIZE; + + /* set non-periodic transmit fifo start address and depth */ + usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH2_RX_FIFO_SIZE; + usbx->gnptxfsiz_ept0tx_bit.nptxfdep = USBH2_NP_TX_FIFO_SIZE; + + /* set periodic transmit fifo start address and depth */ + usbx->hptxfsiz_bit.ptxfstaddr = USBH2_RX_FIFO_SIZE + USBH2_NP_TX_FIFO_SIZE; + usbx->hptxfsiz_bit.ptxfsize = USBH2_P_TX_FIFO_SIZE; + } +#endif + /* flush tx fifo */ + usb_flush_tx_fifo(usbx, 16); + + /* flush rx fifo */ + usb_flush_rx_fifo(usbx); + + /* clear host channel interrut mask and status */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + USB_CHL(usbx, i_index)->hcintmsk = 0; + USB_CHL(usbx, i_index)->hcint = 0xFFFFFFFF; + } + + /* power on to this port */ + usb_port_power_on(usbx, TRUE); + + /* clear global interrupt mask and status */ + usbx->gintmsk = 0; + usbx->gintsts = 0xBFFFFFFF; + + /* set global interrut mask */ + usbx->gintmsk = USB_OTG_SOF_INT | USB_OTG_RXFLVL_INT | + USB_OTG_USBSUSP_INT | USB_OTG_PRT_INT | + USB_OTG_HCH_INT | USB_OTG_INCOMISOIN_INT | + USB_OTG_INCOMPIP_INCOMPISOOUT_INT | USB_OTG_WKUP_INT | + USB_OTG_DISCON_INT; + + /* enable usb global interrupt */ + usb_interrupt_enable(usbx); + + /* active vbus */ + usbh_active_vbus(uhost, TRUE); + return status; +} + +/** + * @brief usb host open channel + * @param uhost: to the structure of usbh_core_type + * @param chn: host channel number + * @param ept_num: devvice endpoint number + * @param dev_address: device address + * @param type: channel transfer type + * this parameter can be one of the following values: + * - EPT_CONTROL_TYPE + * - EPT_BULK_TYPE + * - EPT_INT_TYPE + * - EPT_ISO_TYPE + * @param maxpacket: support max packe size for this channel + * @param speed: device speed + * this parameter can be one of the following values: + * - USB_PRTSPD_FULL_SPEED + * - USB_PRTSPD_LOW_SPEED + * @param ept_addr: endpoint address + * @retval usb_sts_type + */ +void usbh_hc_open(usbh_core_type *uhost, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed) +{ + /* device address */ + uhost->hch[chn].address = dev_address; + + /* device speed */ + uhost->hch[chn].speed = speed; + + /* endpoint transfer type */ + uhost->hch[chn].ept_type = type; + + /* endpoint support maxpacket */ + uhost->hch[chn].maxpacket = maxpacket; + + /* endpoint direction in or out */ + uhost->hch[chn].dir = (ept_num & 0x80)?1:0;; + + /* host channel number */ + uhost->hch[chn].ch_num = chn; + + /* device endpoint number */ + uhost->hch[chn].ept_num = ept_num; + + /* enable channel */ + usb_hc_enable(uhost->usb_reg, chn, + ept_num, dev_address, + type, maxpacket, speed + ); +} + +/** + * @brief disable host channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: channel number + * @retval none + */ +void usbh_ch_disable(usbh_core_type *uhost, uint8_t chn) +{ + usb_hch_halt(uhost->usb_reg, chn); +} + +/** + * @brief usb host alloc channel + * @param uhost: to the structure of usbh_core_type + * @param ept_addr: endpoint address + * @retval usb_sts_type + */ +uint16_t usbh_alloc_channel(usbh_core_type *uhost, uint8_t ept_addr) +{ + /* get one free channel */ + uint16_t ch_num = usbh_get_free_channel(uhost); + + if(ch_num == HCH_ERROR) + return USB_FAIL; + + /* set channel to used */ + uhost->channel[ch_num] = HCH_USED | ept_addr; + return ch_num; +} + +/** + * @brief usb host get urb status + * @param uhost: to the structure of usbh_core_type + * @param ch_num: channel number + * @retval urb_sts_type: urb status + */ +urb_sts_type usbh_get_urb_status(usbh_core_type *uhost, uint8_t ch_num) +{ + return uhost->urb_state[ch_num]; +} +/** + * @brief usb wait control setup complete + * @param uhost: to the structure of usbh_core_type + * @param next_ctrl_state: next ctrl state when setup complete + * @param next_enum_state: next enum state when setup complete + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_result_check(usbh_core_type *uhost, ctrl_ept0_sts_type next_ctrl_state, uint8_t next_enum_state) +{ + usb_sts_type status; + + /* control transfer loop */ + status = usbh_ctrl_transfer_loop(uhost); + + if(status == USB_OK) + { + uhost->ctrl.state = next_ctrl_state; + uhost->enum_state = next_enum_state; + uhost->req_state = CMD_SEND; + } + else if(status == USB_ERROR) + { + uhost->ctrl.state = CONTROL_IDLE; + uhost->req_state = CMD_SEND; + } + else if(status == USB_NOT_SUPPORT) + { + uhost->ctrl.state = next_ctrl_state; + uhost->enum_state = next_enum_state; + uhost->req_state = CMD_SEND; + } + return status; +} + +/** + * @brief auto alloc address (1...20) + * @param none + * @retval address (1...20) + */ +uint8_t usbh_alloc_address(void) +{ + static uint8_t address = 1; + if(address == 20) + address = 1; + return address ++; +} + + +/** + * @brief usb host enumeration handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_enum_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + switch(uhost->enum_state) + { + case ENUM_IDLE: + break; + case ENUM_GET_MIN_DESC: + /* get description */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_device_descriptor(uhost, 8); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_FULL_DESC) == USB_OK) + { + usbh_parse_dev_desc(uhost, uhost->rx_buffer, 8); + + /* set new control endpoint maxpacket size */ + uhost->ctrl.ept0_size = (uhost->dev).dev_desc.bMaxPacketSize0; + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + } + break; + + case ENUM_GET_FULL_DESC: + /* get description */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_device_descriptor(uhost, 18); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_SET_ADDR) == USB_OK) + { + usbh_parse_dev_desc(uhost, uhost->rx_buffer, 18); + USBH_DEBUG("VID: %xh", uhost->dev.dev_desc.idVendor); + USBH_DEBUG("PID: %xh", uhost->dev.dev_desc.idProduct); + } + break; + + case ENUM_SET_ADDR: + /* set device address */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + uhost->dev.address = usbh_alloc_address(); + USBH_DEBUG("Set Address: %d", uhost->dev.address); + usbh_set_address(uhost, uhost->dev.address); + } + if (usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_CFG) == USB_OK) + { + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + } + break; + + case ENUM_GET_CFG: + /* get device confiuration */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_configure_descriptor(uhost, 9); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_FULL_CFG) == USB_OK) + { + usbh_parse_configure_desc(uhost, uhost->rx_buffer, 9); + } + break; + + case ENUM_GET_FULL_CFG: + /* get device confiuration */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_configure_descriptor(uhost, uhost->dev.cfg_desc.cfg.wTotalLength); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_MFC_STRING) == USB_OK) + { + usbh_parse_configure_desc(uhost, uhost->rx_buffer, uhost->dev.cfg_desc.cfg.wTotalLength); + } + break; + + case ENUM_GET_MFC_STRING: + /* get device mfc string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iManufacturer, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_PRODUCT_STRING) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_mfc_string(uhost->rx_buffer); + } + break; + + case ENUM_GET_PRODUCT_STRING: + /* get device product string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iProduct, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_SERIALNUM_STRING) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_product_string(uhost->rx_buffer); + } + break; + + case ENUM_GET_SERIALNUM_STRING: + /* get device serial string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iSerialNumber, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_SET_CONFIG) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_serial_string(uhost->rx_buffer); + } + break; + + case ENUM_SET_CONFIG: + /* set device config */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_set_configuration(uhost, uhost->dev.cfg_desc.cfg.bConfigurationValue); + } + usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_COMPLETE); + + break; + + case ENUM_COMPLETE: + /* enum complete */ + status = USB_OK; + break; + default: + break; + } + return status; +} + +/** + * @brief active vbus. + * @param uhost: to the structure of usbh_core_type + * @param state: vbus state + * @retval none + */ +void usbh_active_vbus(usbh_core_type *uhost, confirm_state state) +{ + uhost->user_handler->user_active_vbus(uhost, state); +} + +/** + * @brief reset usb port + * @param usbx: to the structure of otg_global_type + * @retval none + */ +void usbh_reset_port(usbh_core_type *uhost) +{ + otg_host_type *usb_host = OTG_HOST(uhost->usb_reg); + uint32_t hprt_val = usb_host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + /* set port reset */ + usb_host->hprt = hprt_val | USB_OTG_HPRT_PRTRST; + + usb_delay_ms(100); + + /* clear port reset */ + usb_host->hprt = hprt_val & (~USB_OTG_HPRT_PRTRST); + + usb_delay_ms(20); + +} + +/** + * @brief usb host attached + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_attached(usbh_core_type *uhost) +{ + /* get free channel */ + uhost->ctrl.hch_in = usbh_alloc_channel(uhost, 0x80); + uhost->ctrl.hch_out = usbh_alloc_channel(uhost, 0x00); + + /* user reset callback handler */ + uhost->user_handler->user_reset(); + + /* get device speed */ + uhost->dev.speed = OTG_HOST(uhost->usb_reg)->hprt_bit.prtspd; + uhost->global_state = USBH_ENUMERATION; + uhost->user_handler->user_speed(uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + usb_flush_tx_fifo(uhost->usb_reg, 0x10); + usb_flush_rx_fifo(uhost->usb_reg); + + /* user attached callback */ + uhost->user_handler->user_attached(); +} + + +/** + * @brief usb host enumeration + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_enumeration(usbh_core_type *uhost) +{ + /* enumeration process */ + if(usbh_enum_handler(uhost) == USB_OK) + { + /* user enumeration done callback */ + uhost->user_handler->user_enumeration_done(); + uhost->global_state = USBH_USER_HANDLER; + } +} + +/** + * @brief usb host class request + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_class_request(usbh_core_type *uhost) +{ + usb_sts_type status; + + /* class request callback */ + status = uhost->class_handler->request_handler((void *)uhost); + if(status == USB_OK) + { + uhost->global_state = USBH_CLASS; + } + else if(status == USB_ERROR || status == USB_FAIL) + { + uhost->global_state = USBH_ERROR_STATE; + } + else if(status == USB_NOT_SUPPORT) + { + uhost->global_state = USBH_ERROR_STATE; + } +} + +/** + * @brief usb host class handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_class(usbh_core_type *uhost) +{ + /* process handler */ + if(uhost->class_handler->process_handler((void *)uhost) == USB_OK) + { + } +} + +/** + * @brief usb host suspend + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_suspend(usbh_core_type *uhost) +{ + /* set device feature */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_set_feature(uhost, 0x01, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + /* enter suspend mode */ + usb_delay_ms(3); + usbh_enter_suspend(uhost); + uhost->global_state = USBH_SUSPENDED; + + } +} + +/** + * @brief usb host wakeup + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_wakeup(usbh_core_type *uhost) +{ + /* clear device feature */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + /* usb host resume */ + usbh_resume(uhost); + usbh_clear_dev_feature(uhost, 0x01, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + uhost->global_state = USBH_CLASS_REQUEST; + USBH_DEBUG("Remote Wakeup"); + } +} + +/** + * @brief usb host disconnect + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_disconnect(usbh_core_type *uhost) +{ + uint8_t i_index = 0; + + /* set host to default state */ + usbh_cfg_default_init(uhost); + + /* free host channel */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + usbh_free_channel(uhost, i_index); + } + + /* call class reset handler */ + if(uhost->class_handler->reset_handler != NULL) + { + uhost->class_handler->reset_handler(uhost); + } + + /* set global state to idle */ + uhost->global_state = USBH_IDLE; + + /*call user disconnect function */ + uhost->user_handler->user_disconnect(); +} + + +/** + * @brief usb host enum loop handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +usb_sts_type usbh_loop_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_FAIL; + + if(uhost->conn_sts == 0 && + uhost->global_state != USBH_IDLE && + uhost->global_state != USBH_DISCONNECT) + { + uhost->global_state = USBH_IDLE; + } + switch(uhost->global_state) + { + case USBH_IDLE: + if(uhost->conn_sts == 1) + { + uhost->global_state = USBH_PORT_EN; + + /* wait stable */ + usb_delay_ms(200); + + /* port reset */ + usbh_reset_port(uhost); + + /* user reset */ + uhost->user_handler->user_reset(); + } + break; + + case USBH_PORT_EN: + if(uhost->port_enable) + { + uhost->global_state = USBH_ATTACHED; + usb_delay_ms(50); + } + break; + + case USBH_ATTACHED: + usbh_attached(uhost); + break; + + case USBH_ENUMERATION: + usbh_enumeration(uhost); + break; + + case USBH_USER_HANDLER: + uhost->global_state = USBH_CLASS_REQUEST; + if( uhost->class_handler->init_handler(uhost) == USB_NOT_SUPPORT) + { + uhost->global_state = USBH_UNSUPPORT; + } + break; + + case USBH_CLASS_REQUEST: + usbh_class_request(uhost); + break; + + case USBH_CLASS: + usbh_class(uhost); + break; + + case USBH_SUSPEND: + usbh_suspend(uhost); + break; + + case USBH_SUSPENDED: + break; + + case USBH_WAKEUP: + usbh_wakeup(uhost); + break; + + case USBH_DISCONNECT: + usbh_disconnect(uhost); + break; + + case USBH_ERROR_STATE: + usbh_cfg_default_init(uhost); + uhost->class_handler->reset_handler(uhost); + uhost->user_handler->user_reset(); + break; + case USBH_UNSUPPORT: + break; + default: + break; + } + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c new file mode 100644 index 0000000000..d60ae0a455 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c @@ -0,0 +1,976 @@ +/** + ************************************************************************** + * @file usbh_ctrl.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host control request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_ctrl.h" +#include "usbh_core.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_control + * @brief usb host drivers control + * @{ + */ + +/** @defgroup USBH_ctrl_private_functions + * @{ + */ + +/* control timeout 5s */ +#define CTRL_TIMEOUT 5000 + +/** + * @brief usb host control send setup packet + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control setup send buffer + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num) +{ + uhost->hch[hc_num].dir = 0; + uhost->hch[hc_num].data_pid = HCH_PID_SETUP; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = 8; /*setup */ + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control receive data from device + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control receive data buffer + * @param length: usb control receive data length + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num) +{ + uhost->hch[hc_num].dir = 1; + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = length; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control send data packet + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control send data buffer + * @param length: usb control send data length + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num) +{ + uhost->hch[hc_num].dir = 0; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = length; + + if(length == 0) + { + uhost->hch[uhost->ctrl.hch_out].toggle_out = 1; + } + if(uhost->hch[uhost->ctrl.hch_out].toggle_out == 0) + { + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control setup request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost) +{ + usbh_ctrl_send_setup(uhost, (uint8_t *)(&uhost->ctrl.setup), + uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_SETUP_WAIT; + return USB_OK; +} + +/** + * @brief usb host control setup request wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: pointer of wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout) +{ + urb_sts_type urb_state; + usb_sts_type status = USB_WAIT; + uint8_t dir; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + dir = uhost->ctrl.setup.bmRequestType & USB_REQUEST_DIR_MASK; + if(uhost->ctrl.setup.wLength != 0) + { + *timeout = DATA_STAGE_TIMEOUT; + if(dir == USB_DIR_D2H) //in + { + uhost->ctrl.state = CONTROL_DATA_IN; + } + else //out + { + uhost->ctrl.state = CONTROL_DATA_OUT; + } + } + else + { + *timeout = NODATA_STAGE_TIMEOUT; + if(dir == USB_DIR_D2H) //no data, send status + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else //out + { + uhost->ctrl.state = CONTROL_STATUS_IN; + } + } + status = USB_OK; + } + else if(urb_state == URB_ERROR || urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control data in request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + usbh_ctrl_recv_data(uhost, uhost->ctrl.buffer, + uhost->ctrl.len, + uhost->ctrl.hch_in); + uhost->ctrl.state = CONTROL_DATA_IN_WAIT; + + return status; +} + +/** + * @brief usb host control data in wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_in]; + + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + + } + return status; +} + +/** + * @brief usb host control data out request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + uhost->hch[uhost->ctrl.hch_out].toggle_out = 1; + + usbh_ctrl_send_data(uhost, uhost->ctrl.buffer, + uhost->ctrl.len, + uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_DATA_OUT_WAIT; + + return status; +} + +/** + * @brief usb host control data out wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_STATUS_IN; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else if(urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_DATA_OUT; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control status data in handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + usbh_ctrl_recv_data(uhost, 0, 0, + uhost->ctrl.hch_in); + uhost->ctrl.state = CONTROL_STATUS_IN_WAIT; + + + return status; +} + +/** + * @brief usb host control status data in wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_in]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_COMPLETE; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + status = USB_NOT_SUPPORT; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control status data out wait handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + uhost->hch[uhost->ctrl.hch_out].toggle_out ^= 1; + + usbh_ctrl_send_data(uhost, 0, 0, uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_STATUS_OUT_WAIT; + + return status; +} + +/** + * @brief usb host control status data out wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_COMPLETE; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else if(urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control error handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + if(++ uhost->ctrl.err_cnt <= USBH_MAX_ERROR_COUNT) + { + uhost->ctrl.state = CONTROL_SETUP; + } + else + { + uhost->ctrl.sts = CTRL_FAIL; + uhost->global_state = USBH_ERROR_STATE; + uhost->ctrl.err_cnt = 0; + USBH_DEBUG("control error: **** Device No Response ****"); + status = USB_ERROR; + } + return status; +} + +/** + * @brief usb host control stall handler + * @param uhost: to the structure of usbh_core_type + * @retval usb_sts_type + */ +usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost) +{ + return USB_NOT_SUPPORT; +} + +/** + * @brief usb host control complete handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost) +{ + return USB_OK; +} + +/** + * @brief usb host control transfer loop function + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + static uint32_t timeout = 0; + uhost->ctrl.sts = CTRL_START; + + switch(uhost->ctrl.state) + { + case CONTROL_SETUP: + usbh_ctrl_setup_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_SETUP_WAIT: + usbh_ctrl_setup_wait_handler(uhost, &timeout); + break; + + case CONTROL_DATA_IN: + usbh_ctrl_data_in_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_DATA_IN_WAIT: + usbh_ctrl_data_in_wait_handler(uhost, timeout); + break; + + case CONTROL_DATA_OUT: + usbh_ctrl_data_out_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_DATA_OUT_WAIT: + usbh_ctrl_data_out_wait_handler(uhost, timeout); + break; + + case CONTROL_STATUS_IN: + usbh_ctrl_status_in_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_STATUS_IN_WAIT: + usbh_ctrl_status_in_wait_handler(uhost, timeout); + break; + + case CONTROL_STATUS_OUT: + usbh_ctrl_status_out_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_STATUS_OUT_WAIT: + usbh_ctrl_status_out_wait_handler(uhost, timeout); + break; + case CONTROL_STALL: + status = usbh_ctrl_stall_handler(uhost); + break; + case CONTROL_ERROR: + status = usbh_ctrl_error_handler(uhost); + break; + case CONTROL_COMPLETE: + status = usbh_ctrl_complete_handler(uhost); + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host control request + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb request buffer + * @param length: usb request length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length) +{ + usb_sts_type status = USB_OK; + if(uhost->req_state == CMD_SEND) + { + uhost->req_state = CMD_WAIT; + uhost->ctrl.buffer = buffer; + uhost->ctrl.len = length; + uhost->ctrl.state = CONTROL_SETUP; + } + return status; +} + +/** + * @brief usb host get device descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get descriptor request length + * @param req_type: usb request type + * @param wvalue: usb wvalue + * @param buffer: request buffer + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length, + uint8_t req_type, uint16_t wvalue, + uint8_t *buffer) +{ + usb_sts_type status; + uhost->ctrl.setup.bmRequestType = USB_DIR_D2H | req_type; + uhost->ctrl.setup.bRequest = USB_STD_REQ_GET_DESCRIPTOR; + uhost->ctrl.setup.wValue = wvalue; + uhost->ctrl.setup.wLength = length; + + if((wvalue & 0xFF00) == ((USB_DESCIPTOR_TYPE_STRING << 8) & 0xFF00)) + { + uhost->ctrl.setup.wIndex = 0x0409; + } + else + { + uhost->ctrl.setup.wIndex = 0; + } + + status = usbh_ctrl_request(uhost, buffer, length); + return status; +} + +/** + * @brief usb host parse device descriptor + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb device descriptor buffer + * @param length: usb device descriptor length + * @retval status: usb_sts_type status + */ +void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length) +{ + usbh_dev_desc_type *desc = &(uhost->dev); + + desc->dev_desc.bLength = *(uint8_t *)(buffer + 0); + desc->dev_desc.bDescriptorType = *(uint8_t *)(buffer + 1); + desc->dev_desc.bcdUSB = SWAPBYTE(buffer + 2); + desc->dev_desc.bDeviceClass = *(uint8_t *)(buffer + 4); + desc->dev_desc.bDeviceSubClass = *(uint8_t *)(buffer + 5); + desc->dev_desc.bDeviceProtocol = *(uint8_t *)(buffer + 6); + desc->dev_desc.bMaxPacketSize0 = *(uint8_t *)(buffer + 7); + + if(length > 8) + { + desc->dev_desc.idVendor = SWAPBYTE(buffer + 8); + desc->dev_desc.idProduct = SWAPBYTE(buffer + 10); + desc->dev_desc.bcdDevice = SWAPBYTE(buffer + 12); + desc->dev_desc.iManufacturer = *(uint8_t *)(buffer + 14); + desc->dev_desc.iProduct = *(uint8_t *)(buffer + 15); + desc->dev_desc.iSerialNumber = *(uint8_t *)(buffer + 16); + desc->dev_desc.bNumConfigurations = *(uint8_t *)(buffer + 17); + } +} + +/** + * @brief usb host get next header + * @param buffer: usb data buffer + * @param index_len: pointer of index len + * @retval status: usb_sts_type status + */ +usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len) +{ + *index_len += ((usb_header_desc_type *)buf)->bLength; + return (usb_header_desc_type *) + ((uint8_t *)buf + ((usb_header_desc_type *)buf)->bLength); +} + +/** + * @brief usb host parse interface descriptor + * @param intf: usb interface description type + * @param buf: interface description data buffer + * @retval none + */ +void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf) +{ + intf->bLength = *(uint8_t *)buf; + intf->bDescriptorType = *(uint8_t *)(buf + 1); + intf->bInterfaceNumber = *(uint8_t *)(buf + 2); + intf->bAlternateSetting = *(uint8_t *)(buf + 3); + intf->bNumEndpoints = *(uint8_t *)(buf + 4); + intf->bInterfaceClass = *(uint8_t *)(buf + 5); + intf->bInterfaceSubClass = *(uint8_t *)(buf + 6); + intf->bInterfaceProtocol = *(uint8_t *)(buf + 7); + intf->iInterface = *(uint8_t *)(buf + 8); +} + +/** + * @brief usb host parse endpoint descriptor + * @param ept_desc: endpoint type + * @param buf: endpoint description data buffer + * @retval none + */ +void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf) +{ + ept_desc->bLength = *(uint8_t *)(buf + 0); + ept_desc->bDescriptorType = *(uint8_t *)(buf + 1); + ept_desc->bEndpointAddress = *(uint8_t *)(buf + 2); + ept_desc->bmAttributes = *(uint8_t *)(buf + 3); + ept_desc->wMaxPacketSize = SWAPBYTE(buf + 4); + ept_desc->bInterval = *(uint8_t *)(buf + 6); +} + +/** + * @brief usb host parse configure descriptor + * @param uhost: to the structure of usbh_core_type + * @param buffer: configure buffer + * @param length: configure length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost, + uint8_t *buffer, uint16_t length) +{ + usb_cfg_desc_type *cfg_desc = &(uhost->dev.cfg_desc); + usb_interface_desc_type *intf_desc; + usb_endpoint_desc_type *ept_desc; + usb_header_desc_type *desc; + uint16_t index_len; + uint8_t index_intf = 0; + uint8_t index_ept = 0; + + desc = (usb_header_desc_type *)buffer; + cfg_desc->cfg.bLength = *(uint8_t *)buffer; + cfg_desc->cfg.bDescriptorType = *(uint8_t *)(buffer + 1); + cfg_desc->cfg.wTotalLength = SWAPBYTE(buffer + 2); + cfg_desc->cfg.bNumInterfaces = *(uint8_t *)(buffer + 4); + cfg_desc->cfg.bConfigurationValue = *(uint8_t *)(buffer + 5); + cfg_desc->cfg.iConfiguration = *(uint8_t *)(buffer + 6); + cfg_desc->cfg.bmAttributes = *(uint8_t *)(buffer + 7); + cfg_desc->cfg.bMaxPower = *(uint8_t *)(buffer + 8); + + if(length > USB_DEVICE_CFG_DESC_LEN) + { + index_len = USB_DEVICE_CFG_DESC_LEN; + + while((index_intf < USBH_MAX_INTERFACE) && index_len < cfg_desc->cfg.wTotalLength) + { + desc = usbh_get_next_header((uint8_t *)desc, &index_len); + if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_INTERFACE) + { + index_ept = 0; + intf_desc = &cfg_desc->interface[index_intf].interface; + usbh_parse_interface_desc(intf_desc, (uint8_t *)desc); + + while(index_ept < intf_desc->bNumEndpoints && index_len < cfg_desc->cfg.wTotalLength) + { + desc = usbh_get_next_header((uint8_t *)desc, &index_len); + if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_ENDPOINT) + { + ept_desc = &(cfg_desc->interface[index_intf].endpoint[index_ept]); + usbh_parse_endpoint_desc(ept_desc, (uint8_t *)desc); + index_ept ++; + } + } + index_intf ++; + } + } + } + return USB_OK; +} + +/** + * @brief usb host find interface + * @param uhost: to the structure of usbh_core_type + * @param class_code: class code + * @param sub_class: subclass code + * @param protocol: prtocol code + * @retval idx: interface index + */ +uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol) +{ + uint8_t idx = 0; + usb_itf_desc_type *usbitf; + for(idx = 0; idx < uhost->dev.cfg_desc.cfg.bNumInterfaces; idx ++) + { + usbitf = &uhost->dev.cfg_desc.interface[idx]; + if(((usbitf->interface.bInterfaceClass == class_code) || (class_code == 0xFF)) && + ((usbitf->interface.bInterfaceSubClass == sub_class) || (sub_class == 0xFF)) && + ((usbitf->interface.bInterfaceProtocol == protocol) || (protocol == 0xFF)) + ) + { + return idx; + } + } + return 0xFF; +} + +/** + * @brief usbh parse string descriptor + * @param src: string source pointer + * @param dest: string destination pointer + * @param length: string length + * @retval none + */ +void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length) +{ + uint16_t len; + uint16_t i_index; + + if(src[1] == USB_DESCIPTOR_TYPE_STRING) + { + len = ((src[0] - 2) <= length ? (src[0] - 2) : length); + src += 2; + for(i_index = 0; i_index < len; i_index += 2) + { + *dest = src[i_index]; + dest ++; + } + *dest = 0; + } +} + +/** + * @brief usb host get device descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get device descriptor length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_DEVICE << 8) & 0xFF00; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + return status; +} + +/** + * @brief usb host get configure descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get device configure length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_CONFIGURATION << 8) & 0xFF00; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + + return status; +} + +/** + * @brief usb host get string descriptor + * @param uhost: to the structure of usbh_core_type + * @param string_id: string id + * @param buffer: receive data buffer + * @param length: get device string length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id, + uint8_t *buffer, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_STRING << 8) | string_id; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + + return status; +} + +/** + * @brief usb host set configurtion + * @param uhost: to the structure of usbh_core_type + * @param config: usb configuration + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_CONFIGURATION; + uhost->ctrl.setup.wValue = config; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = 0; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set device address + * @param uhost: to the structure of usbh_core_type + * @param address: device address + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_ADDRESS; + uhost->ctrl.setup.wValue = (uint16_t)address; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = 0; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set interface + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param altsetting: alter setting + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_INTERFACE; + uhost->ctrl.setup.wValue = (uint16_t)altsetting; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = ept_num; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set feature + * @param uhost: to the structure of usbh_core_type + * @param feature: feature number + * @param index: index number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_FEATURE; + uhost->ctrl.setup.wValue = (uint16_t)feature; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = index; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + + +/** + * @brief usb host clear device feature + * @param uhost: to the structure of usbh_core_type + * @param feature: feature number + * @param index: index number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + uhost->ctrl.setup.wValue = (uint16_t)feature; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = index; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host clear endpoint feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param hc_num: host channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + if(uhost->ctrl.state == CONTROL_IDLE ) + { + bm_req = USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + uhost->ctrl.setup.wValue = USB_FEATURE_EPT_HALT; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = ept_num; + usbh_ctrl_request(uhost, 0, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c new file mode 100644 index 0000000000..81b37dc28c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c @@ -0,0 +1,529 @@ +/** + ************************************************************************** + * @file usbh_int.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host interrupt request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_int.h" + + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_interrupt + * @brief usb host interrupt + * @{ + */ + +/** @defgroup USBH_int_private_functions + * @{ + */ + +/** + * @brief usb host interrupt handler + * @param otgdev: to the structure of otg_core_type + * @retval none + */ +void usbh_irq_handler(otg_core_type *otgdev) +{ + otg_global_type *usbx = otgdev->usb_reg; + usbh_core_type *uhost = &otgdev->host; + uint32_t intsts = usb_global_get_all_interrupt(usbx); + + if(usbx->gintsts_bit.curmode == 1) + { + if(intsts & USB_OTG_HCH_FLAG) + { + usbh_hch_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_HCH_FLAG); + } + if(intsts & USB_OTG_SOF_FLAG) + { + usbh_sof_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG); + } + if(intsts & USB_OTG_MODEMIS_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG); + } + if(intsts & USB_OTG_WKUP_FLAG) + { + usbh_wakeup_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG); + } + while(usbx->gintsts & USB_OTG_RXFLVL_FLAG) + { + usbh_rx_qlvl_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_RXFLVL_FLAG); + } + if(intsts & USB_OTG_DISCON_FLAG) + { + usbh_disconnect_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_DISCON_FLAG); + } + if(intsts & USB_OTG_PRT_FLAG) + { + usbh_port_handler(uhost); + } + if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG); + } + if(intsts & USB_OTG_INCOMISOIN_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG); + } + if(intsts & USB_OTG_PTXFEMP_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_PTXFEMP_FLAG); + } + if(intsts & USB_OTG_ISOOUTDROP_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_ISOOUTDROP_FLAG); + } + + } +} + +/** + * @brief usb host wakeup handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_wakeup_handler(usbh_core_type *uhost) +{ + uhost->global_state = USBH_WAKEUP; +} + +/** + * @brief usb host sof handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_sof_handler(usbh_core_type *uhost) +{ + uhost->timer ++; +} + +/** + * @brief usb host disconnect handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_disconnect_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + + uint8_t i_index; + + usb_host_disable(usbx); + + uhost->conn_sts = 0; + + uhost->global_state = USBH_DISCONNECT; + + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + usbh_free_channel(uhost, i_index); + } + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); +} + +/** + * @brief usb host in transfer request handler + * @param uhost: to the structure of usbh_core_type + * @param chn: channel number + * @retval none + */ +void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk; + + if( hcint_value & USB_OTG_HC_ACK_FLAG) + { + usb_chh->hcint = USB_OTG_HC_ACK_FLAG; + } + else if(hcint_value & USB_OTG_HC_STALL_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG | USB_OTG_HC_STALL_FLAG; + uhost->hch[chn].state = HCH_STALL; + usb_hch_halt(usbx, chn); + } + else if(hcint_value & USB_OTG_HC_DTGLERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG; + uhost->hch[chn].state = HCH_DATATGLERR; + } + + else if(hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG; + } + else if(hcint_value & USB_OTG_HC_XFERC_FLAG) + { + uhost->hch[chn].state = HCH_XFRC; + usb_chh->hcint = USB_OTG_HC_XFERC_FLAG; + + if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE || usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } + else if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE) + { + usb_chh->hcchar_bit.oddfrm = TRUE; + uhost->urb_state[chn] = URB_DONE; + } + else if(usb_chh->hcchar_bit.eptype == EPT_ISO_TYPE) + { + uhost->urb_state[chn] = URB_DONE; + } + uhost->hch[chn].toggle_in ^= 1; + } + else if(hcint_value & USB_OTG_HC_CHHLTD_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = FALSE; + if(uhost->hch[chn].state == HCH_XFRC ) + { + uhost->urb_state[chn] = URB_DONE; + } + else if(uhost->hch[chn].state == HCH_STALL) + { + uhost->urb_state[chn] = URB_STALL; + } + else if(uhost->hch[chn].state == HCH_XACTERR || + uhost->hch[chn].state == HCH_DATATGLERR) + { + uhost->err_cnt[chn] ++; + if(uhost->err_cnt[chn] > 3) + { + uhost->urb_state[chn] = URB_ERROR; + uhost->err_cnt[chn] = 0; + } + else + { + uhost->urb_state[chn] = URB_NOTREADY; + } + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + } + else if(uhost->hch[chn].state == HCH_NAK) + { + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + uhost->urb_state[chn] = URB_NOTREADY; + } + usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG; + } + else if(hcint_value & USB_OTG_HC_XACTERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->hch[chn].state = HCH_XACTERR; + usb_hch_halt(usbx, chn); + uhost->err_cnt[chn] ++; + usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG; + } + else if(hcint_value & USB_OTG_HC_NAK_FLAG) + { + if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE) + { + uhost->err_cnt[chn] = 0; + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + } + else if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE || + usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE) + { + uhost->err_cnt[chn] = 0; + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + } + uhost->hch[chn].state = HCH_NAK; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } + else if(hcint_value & USB_OTG_HC_BBLERR_FLAG) + { + usb_chh->hcint = USB_OTG_HC_BBLERR_FLAG; + } +} + +/** + * @brief usb host out transfer request handler + * @param uhost: to the structure of usbh_core_type + * @param chn: channel number + * @retval none + */ +void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk; + + if( hcint_value & USB_OTG_HC_ACK_FLAG) + { + usb_chh->hcint = USB_OTG_HC_ACK_FLAG; + } + else if( hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG; + } + else if( hcint_value & USB_OTG_HC_XFERC_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + uhost->hch[chn].state = HCH_XFRC; + usb_chh->hcint = USB_OTG_HC_XFERC_FLAG; + } + else if( hcint_value & USB_OTG_HC_STALL_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_chh->hcint = USB_OTG_HC_STALL_FLAG; + uhost->hch[chn].state = HCH_STALL; + usb_hch_halt(usbx, chn); + } + else if( hcint_value & USB_OTG_HC_DTGLERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG; + uhost->hch[chn].state = HCH_DATATGLERR; + } + else if( hcint_value & USB_OTG_HC_CHHLTD_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = FALSE; + if(uhost->hch[chn].state == HCH_XFRC) + { + uhost->urb_state[chn] = URB_DONE; + if(uhost->hch[chn].ept_type == EPT_BULK_TYPE || + uhost->hch[chn].ept_type == EPT_INT_TYPE) + { + uhost->hch[chn].toggle_out ^= 1; + } + } + else if(uhost->hch[chn].state == HCH_NAK) + { + uhost->urb_state[chn] = URB_NOTREADY; + } + else if(uhost->hch[chn].state == HCH_STALL) + { + uhost->hch[chn].urb_sts = URB_STALL; + } + else if(uhost->hch[chn].state == HCH_XACTERR || + uhost->hch[chn].state == HCH_DATATGLERR) + { + uhost->err_cnt[chn] ++; + if(uhost->err_cnt[chn] > 3) + { + uhost->urb_state[chn] = URB_ERROR; + uhost->err_cnt[chn] = 0; + } + else + { + uhost->urb_state[chn] = URB_NOTREADY; + } + + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + } + usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG; + } + else if( hcint_value & USB_OTG_HC_XACTERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->err_cnt[chn] ++; + uhost->hch[chn].state = HCH_XACTERR; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG | USB_OTG_HC_NAK_FLAG; + } + else if( hcint_value & USB_OTG_HC_NAK_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->err_cnt[chn] = 0; + usb_hch_halt(usbx, chn); + uhost->hch[chn].state = HCH_NAK; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } +} + +/** + * @brief usb host channel request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_hch_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_host_type *usb_host = OTG_HOST(usbx); + uint32_t intsts, i_index; + + intsts = usb_host->haint & 0xFFFF; + for(i_index = 0; i_index < 16; i_index ++) + { + if(intsts & (1 << i_index)) + { + if(USB_CHL(usbx, i_index)->hcchar_bit.eptdir) + { + //hc in + usbh_hch_in_handler(uhost, i_index); + } + else + { + //hc out + usbh_hch_out_handler(uhost, i_index); + } + } + } +} + +/** + * @brief usb host rx buffer not empty request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_rx_qlvl_handler(usbh_core_type *uhost) +{ + uint8_t chn; + uint32_t pktsts; + uint32_t pktcnt; + uint32_t tmp; + otg_hchannel_type *ch; + otg_global_type *usbx = uhost->usb_reg; + + usbx->gintmsk_bit.rxflvlmsk = 0; + + tmp = usbx->grxstsp; + chn = tmp & 0xF; + pktsts = (tmp >> 17) & 0xF; + pktcnt = (tmp >> 4) & 0x7FF; + ch = USB_CHL(usbx, chn); + switch(pktsts) + { + case PKTSTS_IN_DATA_PACKET_RECV: + if(pktcnt > 0 && (uhost->hch[chn].trans_buf) != 0) + { + usb_read_packet(usbx, uhost->hch[chn].trans_buf, chn, pktcnt); + uhost->hch[chn].trans_buf += pktcnt; + uhost->hch[chn].trans_count += pktcnt; + + if(ch->hctsiz_bit.pktcnt > 0) + { + ch->hcchar_bit.chdis = FALSE; + ch->hcchar_bit.chena = TRUE; + uhost->hch[chn].toggle_in ^= 1; + } + } + break; + case PKTSTS_IN_TRANSFER_COMPLETE: + break; + case PKTSTS_DATA_BIT_ERROR: + break; + case PKTSTS_CHANNEL_STOP: + break; + default: + break; + + } + usbx->gintmsk_bit.rxflvlmsk = 1; +} + +/** + * @brief usb host port request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_port_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_host_type *usb_host = OTG_HOST(usbx); + + uint32_t prt = 0, prt_0; + + prt = usb_host->hprt; + prt_0 = prt; + + prt_0 &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + if(prt & USB_OTG_HPRT_PRTCONDET) + { + if(prt & USB_OTG_HPRT_PRTCONSTS) + { + /* connect callback */ + uhost->conn_sts = 1; + } + prt_0 |= USB_OTG_HPRT_PRTCONDET; + } + + if(prt & USB_OTG_HPRT_PRTENCHNG) + { + prt_0 |= USB_OTG_HPRT_PRTENCHNG; + + if(prt & USB_OTG_HPRT_PRTENA) + { + if((prt & USB_OTG_HPRT_PRTSPD) == (USB_PRTSPD_LOW_SPEED << 17)) + { + usbh_fsls_clksel(usbx, USB_HCFG_CLK_6M); + } + else + { + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); + } + /* connect callback */ + uhost->port_enable = 1; + } + else + { + /* clean up hprt */ + uhost->port_enable = 0; + } + } + + if(prt & USB_OTG_HPRT_PRTOVRCACT) + { + prt_0 |= USB_OTG_HPRT_PRTOVRCACT; + } + + usb_host->hprt = prt_0; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index 2ded047b05..d97e6d300c 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -51,7 +51,10 @@ #define EXTENDED_FASTRAM #endif -#ifdef STM32H7 +#if defined (STM32H7) +#define DMA_RAM __attribute__ ((section(".DMA_RAM"))) +#define SLOW_RAM __attribute__ ((section(".SLOW_RAM"))) +#elif defined (AT32F43x) #define DMA_RAM __attribute__ ((section(".DMA_RAM"))) #define SLOW_RAM __attribute__ ((section(".SLOW_RAM"))) #else diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 134e649dfa..92a7967afb 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -52,7 +52,9 @@ #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms +#ifndef UNUSED #define UNUSED(x) ((void)(x)) +#endif #define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE" #define FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE "WAITING FOR IDLE" #define FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION "READY TO LAUNCH" diff --git a/src/main/platform.h b/src/main/platform.h index 42fa4ff938..8c4429746d 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -57,6 +57,19 @@ #define U_ID_2 (*(uint32_t*)0x1ff0f428) #endif +#elif defined(AT32F43x) +#include "at32f435_437.h" + +#define U_ID_0 (*(uint32_t*)0x1FFFF7E8) +#define U_ID_1 (*(uint32_t*)0x1FFFF7EC) +#define U_ID_2 (*(uint32_t*)0x1FFFF7F0) +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + #elif defined(STM32F4) #include "stm32f4xx.h" diff --git a/src/main/startup/startup_at32f435_437.s b/src/main/startup/startup_at32f435_437.s new file mode 100644 index 0000000000..dc4fd4e582 --- /dev/null +++ b/src/main/startup/startup_at32f435_437.s @@ -0,0 +1,577 @@ +/** + ****************************************************************************** + * @file startup_at32f435_437.s + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 devices vector table for gcc toolchain. + * this module performs: + * - set the initial sp + * - set the initial pc == reset_handler, + * - set the vector table entries with the exceptions isr address + * - configure the clock system and the external sram to + * be used as data memory (optional, to be enabled by user) + * - branches to main in the c library (which eventually + * calls main()). + * after reset the cortex-m4 processor is in thread mode, + * priority is privileged, and the stack is set to main. + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* custom init */ + ldr sp, =_estack /* set stack pointer */ + + bl persistentObjectInit + bl checkForBootLoaderRequest + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDT_IRQHandler /* Window Watchdog Timer */ + .word PVM_IRQHandler /* PVM through EXINT Line detect */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXINT line */ + .word ERTC_WKUP_IRQHandler /* ERTC Wakeup through the EXINT line */ + .word FLASH_IRQHandler /* Flash */ + .word CRM_IRQHandler /* CRM */ + .word EXINT0_IRQHandler /* EXINT Line 0 */ + .word EXINT1_IRQHandler /* EXINT Line 1 */ + .word EXINT2_IRQHandler /* EXINT Line 2 */ + .word EXINT3_IRQHandler /* EXINT Line 3 */ + .word EXINT4_IRQHandler /* EXINT Line 4 */ + .word EDMA_Stream1_IRQHandler /* EDMA Stream 1 */ + .word EDMA_Stream2_IRQHandler /* EDMA Stream 2 */ + .word EDMA_Stream3_IRQHandler /* EDMA Stream 3 */ + .word EDMA_Stream4_IRQHandler /* EDMA Stream 4 */ + .word EDMA_Stream5_IRQHandler /* EDMA Stream 5 */ + .word EDMA_Stream6_IRQHandler /* EDMA Stream 6 */ + .word EDMA_Stream7_IRQHandler /* EDMA Stream 7 */ + .word ADC1_2_3_IRQHandler /* ADC1 & ADC2 & ADC3 */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SE_IRQHandler /* CAN1 SE */ + .word EXINT9_5_IRQHandler /* EXINT Line [9:5] */ + .word TMR1_BRK_TMR9_IRQHandler /* TMR1 Brake and TMR9 */ + .word TMR1_OVF_TMR10_IRQHandler /* TMR1 Overflow and TMR10 */ + .word TMR1_TRG_HALL_TMR11_IRQHandler /* TMR1 Trigger and hall and TMR11 */ + .word TMR1_CH_IRQHandler /* TMR1 Channel */ + .word TMR2_GLOBAL_IRQHandler /* TMR2 */ + .word TMR3_GLOBAL_IRQHandler /* TMR3 */ + .word TMR4_GLOBAL_IRQHandler /* TMR4 */ + .word I2C1_EVT_IRQHandler /* I2C1 Event */ + .word I2C1_ERR_IRQHandler /* I2C1 Error */ + .word I2C2_EVT_IRQHandler /* I2C2 Event */ + .word I2C2_ERR_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_I2S2EXT_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXINT15_10_IRQHandler /* EXINT Line [15:10] */ + .word ERTCAlarm_IRQHandler /* RTC Alarm through EXINT Line */ + .word OTGFS1_WKUP_IRQHandler /* OTGFS1 Wakeup from suspend */ + .word TMR8_BRK_TMR12_IRQHandler /* TMR8 Brake and TMR12 */ + .word TMR8_OVF_TMR13_IRQHandler /* TMR8 Overflow and TMR13 */ + .word TMR8_TRG_HALL_TMR14_IRQHandler /* TMR8 Trigger and hall and TMR14 */ + .word TMR8_CH_IRQHandler /* TMR8 Channel */ + .word EDMA_Stream8_IRQHandler /* EDMA Stream 8 */ + .word XMC_IRQHandler /* XMC */ + .word SDIO1_IRQHandler /* SDIO1 */ + .word TMR5_GLOBAL_IRQHandler /* TMR5 */ + .word SPI3_I2S3EXT_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TMR6_DAC_GLOBAL_IRQHandler /* TMR6 & DAC */ + .word TMR7_GLOBAL_IRQHandler /* TMR7 */ + .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */ + .word DMA1_Channel2_IRQHandler /* DMA1 Channel 2 */ + .word DMA1_Channel3_IRQHandler /* DMA1 Channel 3 */ + .word DMA1_Channel4_IRQHandler /* DMA1 Channel 4 */ + .word DMA1_Channel5_IRQHandler /* DMA1 Channel 5 */ + .word EMAC_IRQHandler /* EMAC */ + .word EMAC_WKUP_IRQHandler /* EMAC Wakeup */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SE_IRQHandler /* CAN2 SE */ + .word OTGFS1_IRQHandler /* OTGFS1 */ + .word DMA1_Channel6_IRQHandler /* DMA1 Channel 6 */ + .word DMA1_Channel7_IRQHandler /* DMA1 Channel 7 */ + .word 0 /* Reserved */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EVT_IRQHandler /* I2C3 Event */ + .word I2C3_ERR_IRQHandler /* I2C3 Error */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word OTGFS2_WKUP_IRQHandler /* OTGFS2 Wakeup from suspend */ + .word OTGFS2_IRQHandler /* OTGFS2 */ + .word DVP_IRQHandler /* DVP */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word QSPI2_IRQHandler /* QSPI2 */ + .word QSPI1_IRQHandler /* QSPI1 */ + .word 0 /* Reserved */ + .word DMAMUX_IRQHandler /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SDIO2_IRQHandler /* SDIO2 */ + .word ACC_IRQHandler /* ACC */ + .word TMR20_BRK_IRQHandler /* TMR20 Brake */ + .word TMR20_OVF_IRQHandler /* TMR20 Overflow */ + .word TMR20_TRG_HALL_IRQHandler /* TMR20 Trigger and hall */ + .word TMR20_CH_IRQHandler /* TMR20 Channel */ + .word DMA2_Channel1_IRQHandler /* DMA2 Channel 1 */ + .word DMA2_Channel2_IRQHandler /* DMA2 Channel 2 */ + .word DMA2_Channel3_IRQHandler /* DMA2 Channel 3 */ + .word DMA2_Channel4_IRQHandler /* DMA2 Channel 4 */ + .word DMA2_Channel5_IRQHandler /* DMA2 Channel 5 */ + .word DMA2_Channel6_IRQHandler /* DMA2 Channel 6 */ + .word DMA2_Channel7_IRQHandler /* DMA2 Channel 7 */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDT_IRQHandler + .thumb_set WWDT_IRQHandler,Default_Handler + + .weak PVM_IRQHandler + .thumb_set PVM_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak ERTC_WKUP_IRQHandler + .thumb_set ERTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak CRM_IRQHandler + .thumb_set CRM_IRQHandler,Default_Handler + + .weak EXINT0_IRQHandler + .thumb_set EXINT0_IRQHandler,Default_Handler + + .weak EXINT1_IRQHandler + .thumb_set EXINT1_IRQHandler,Default_Handler + + .weak EXINT2_IRQHandler + .thumb_set EXINT2_IRQHandler,Default_Handler + + .weak EXINT3_IRQHandler + .thumb_set EXINT3_IRQHandler,Default_Handler + + .weak EXINT4_IRQHandler + .thumb_set EXINT4_IRQHandler,Default_Handler + + .weak EDMA_Stream1_IRQHandler + .thumb_set EDMA_Stream1_IRQHandler,Default_Handler + + .weak EDMA_Stream2_IRQHandler + .thumb_set EDMA_Stream2_IRQHandler,Default_Handler + + .weak EDMA_Stream3_IRQHandler + .thumb_set EDMA_Stream3_IRQHandler,Default_Handler + + .weak EDMA_Stream4_IRQHandler + .thumb_set EDMA_Stream4_IRQHandler,Default_Handler + + .weak EDMA_Stream5_IRQHandler + .thumb_set EDMA_Stream5_IRQHandler,Default_Handler + + .weak EDMA_Stream6_IRQHandler + .thumb_set EDMA_Stream6_IRQHandler,Default_Handler + + .weak EDMA_Stream7_IRQHandler + .thumb_set EDMA_Stream7_IRQHandler,Default_Handler + + .weak ADC1_2_3_IRQHandler + .thumb_set ADC1_2_3_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SE_IRQHandler + .thumb_set CAN1_SE_IRQHandler,Default_Handler + + .weak EXINT9_5_IRQHandler + .thumb_set EXINT9_5_IRQHandler,Default_Handler + + .weak TMR1_BRK_TMR9_IRQHandler + .thumb_set TMR1_BRK_TMR9_IRQHandler,Default_Handler + + .weak TMR1_OVF_TMR10_IRQHandler + .thumb_set TMR1_OVF_TMR10_IRQHandler,Default_Handler + + .weak TMR1_TRG_HALL_TMR11_IRQHandler + .thumb_set TMR1_TRG_HALL_TMR11_IRQHandler,Default_Handler + + .weak TMR1_CH_IRQHandler + .thumb_set TMR1_CH_IRQHandler,Default_Handler + + .weak TMR2_GLOBAL_IRQHandler + .thumb_set TMR2_GLOBAL_IRQHandler,Default_Handler + + .weak TMR3_GLOBAL_IRQHandler + .thumb_set TMR3_GLOBAL_IRQHandler,Default_Handler + + .weak TMR4_GLOBAL_IRQHandler + .thumb_set TMR4_GLOBAL_IRQHandler,Default_Handler + + .weak I2C1_EVT_IRQHandler + .thumb_set I2C1_EVT_IRQHandler,Default_Handler + + .weak I2C1_ERR_IRQHandler + .thumb_set I2C1_ERR_IRQHandler,Default_Handler + + .weak I2C2_EVT_IRQHandler + .thumb_set I2C2_EVT_IRQHandler,Default_Handler + + .weak I2C2_ERR_IRQHandler + .thumb_set I2C2_ERR_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_I2S2EXT_IRQHandler + .thumb_set SPI2_I2S2EXT_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXINT15_10_IRQHandler + .thumb_set EXINT15_10_IRQHandler,Default_Handler + + .weak ERTCAlarm_IRQHandler + .thumb_set ERTCAlarm_IRQHandler,Default_Handler + + .weak OTGFS1_WKUP_IRQHandler + .thumb_set OTGFS1_WKUP_IRQHandler,Default_Handler + + .weak TMR8_BRK_TMR12_IRQHandler + .thumb_set TMR8_BRK_TMR12_IRQHandler,Default_Handler + + .weak TMR8_OVF_TMR13_IRQHandler + .thumb_set TMR8_OVF_TMR13_IRQHandler,Default_Handler + + .weak TMR8_TRG_HALL_TMR14_IRQHandler + .thumb_set TMR8_TRG_HALL_TMR14_IRQHandler,Default_Handler + + .weak TMR8_CH_IRQHandler + .thumb_set TMR8_CH_IRQHandler,Default_Handler + + .weak EDMA_Stream8_IRQHandler + .thumb_set EDMA_Stream8_IRQHandler,Default_Handler + + .weak XMC_IRQHandler + .thumb_set XMC_IRQHandler,Default_Handler + + .weak SDIO1_IRQHandler + .thumb_set SDIO1_IRQHandler,Default_Handler + + .weak TMR5_GLOBAL_IRQHandler + .thumb_set TMR5_GLOBAL_IRQHandler,Default_Handler + + .weak SPI3_I2S3EXT_IRQHandler + .thumb_set SPI3_I2S3EXT_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TMR6_DAC_GLOBAL_IRQHandler + .thumb_set TMR6_DAC_GLOBAL_IRQHandler,Default_Handler + + .weak TMR7_GLOBAL_IRQHandler + .thumb_set TMR7_GLOBAL_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak EMAC_IRQHandler + .thumb_set EMAC_IRQHandler,Default_Handler + + .weak EMAC_WKUP_IRQHandler + .thumb_set EMAC_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler ,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler ,Default_Handler + + .weak CAN2_SE_IRQHandler + .thumb_set CAN2_SE_IRQHandler,Default_Handler + + .weak OTGFS1_IRQHandler + .thumb_set OTGFS1_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EVT_IRQHandler + .thumb_set I2C3_EVT_IRQHandler,Default_Handler + + .weak I2C3_ERR_IRQHandler + .thumb_set I2C3_ERR_IRQHandler,Default_Handler + + .weak OTGFS2_WKUP_IRQHandler + .thumb_set OTGFS2_WKUP_IRQHandler,Default_Handler + + .weak OTGFS2_IRQHandler + .thumb_set OTGFS2_IRQHandler,Default_Handler + + .weak DVP_IRQHandler + .thumb_set DVP_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak QSPI2_IRQHandler + .thumb_set QSPI2_IRQHandler,Default_Handler + + .weak QSPI1_IRQHandler + .thumb_set QSPI1_IRQHandler,Default_Handler + + .weak DMAMUX_IRQHandler + .thumb_set DMAMUX_IRQHandler ,Default_Handler + + .weak SDIO2_IRQHandler + .thumb_set SDIO2_IRQHandler ,Default_Handler + + .weak ACC_IRQHandler + .thumb_set ACC_IRQHandler,Default_Handler + + .weak TMR20_BRK_IRQHandler + .thumb_set TMR20_BRK_IRQHandler,Default_Handler + + .weak TMR20_OVF_IRQHandler + .thumb_set TMR20_OVF_IRQHandler,Default_Handler + + .weak TMR20_TRG_HALL_IRQHandler + .thumb_set TMR20_TRG_HALL_IRQHandler,Default_Handler + + .weak TMR20_CH_IRQHandler + .thumb_set TMR20_CH_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak DMA2_Channel6_IRQHandler + .thumb_set DMA2_Channel6_IRQHandler,Default_Handler + + .weak DMA2_Channel7_IRQHandler + .thumb_set DMA2_Channel7_IRQHandler,Default_Handler diff --git a/src/main/target/link/at32_flash_f43xG.ld b/src/main/target/link/at32_flash_f43xG.ld new file mode 100644 index 0000000000..7d43eae4e3 --- /dev/null +++ b/src/main/target/link/at32_flash_f43xG.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xG.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 1024 Byte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 976K : 992K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM.ld b/src/main/target/link/at32_flash_f43xM.ld new file mode 100644 index 0000000000..2c8d11d0ba --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM_bl.ld b/src/main/target/link/at32_flash_f43xM_bl.ld new file mode 100644 index 0000000000..f0be9d4a56 --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM_bl.ld @@ -0,0 +1,52 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + + +__firmware_start = ORIGIN(FLASH1); +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM_for_bl.ld b/src/main/target/link/at32_flash_f43xM_for_bl.ld new file mode 100644 index 0000000000..1f83b7f38f --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM_for_bl.ld @@ -0,0 +1,52 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x800A800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x0800C000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3952K: 3968K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083E4000 : 0x083E8000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +__firmware_start = ORIGIN(FLASH); +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f4_split.ld b/src/main/target/link/at32_flash_f4_split.ld new file mode 100644 index 0000000000..5a24637974 --- /dev/null +++ b/src/main/target/link/at32_flash_f4_split.ld @@ -0,0 +1,267 @@ +/* +***************************************************************************** +** +** File : at32_flash_f4_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_Hot_Reboot_Flags_Size = 16; +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; /* end of RAM */ + +/* Base address where the config is stored. */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* + * The ISR vector table is loaded at the beginning of the FLASH, + * But it is linked (space reserved) at the beginning of the VECTAB region, + * which is aliased either to FLASH or RAM. + * When linked to RAM, the table can optionally be copied from FLASH to RAM + * for table relocation. + */ + + _isr_vector_table_flash_base = LOADADDR(.isr_vector); + PROVIDE (isr_vector_table_flash_base = _isr_vector_table_flash_base); + + .isr_vector : + { + . = ALIGN(4); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + PROVIDE (isr_vector_table_end = .); + } >FLASH + + + + /* System memory (read-only bootloader) interrupt vector */ + .system_isr_vector (NOLOAD) : + { + . = ALIGN(4); + PROVIDE (system_isr_vector_table_base = .); + KEEP(*(.system_isr_vector)) /* Bootloader code */ + . = ALIGN(4); + } >SYSTEM_MEMORY + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH1 + + + /* Critical program code goes into ZW RAM1 */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >RAM1 AT >FLASH1 + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >MOVABLE_FLASH + + .busdev_registry : + { + PROVIDE_HIDDEN (__busdev_registry_start = .); + KEEP (*(.busdev_registry)) + KEEP (*(SORT(.busdev_registry.*))) + PROVIDE_HIDDEN (__busdev_registry_end = .); + } >MOVABLE_FLASH + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >MOVABLE_FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >MOVABLE_FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >MOVABLE_FLASH + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >MOVABLE_FLASH + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH1 + + /* Storage for the address for the configuration section so we can grab it out of the hex file */ + .custom_defaults : + { + . = ALIGN(4); + KEEP (*(.custom_defaults_start_address)) + . = ALIGN(4); + KEEP (*(.custom_defaults_end_address)) + . = ALIGN(4); + __custom_defaults_internal_start = .; + *(.custom_defaults); + } >FLASH_CUSTOM_DEFAULTS + + PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) : __custom_defaults_internal_start); + PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) + LENGTH(FLASH_CUSTOM_DEFAULTS_EXTENDED) : ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS)); + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> MOVABLE_FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_DATA section for unsuspecting developers */ + /* init in startup/system_at32f43x.c */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT> FLASH1 + +/* define FAST_DATA_ZERO_INIT part Initialized in startup_at23f435_437_.S */ + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >FASTRAM + + .DMA_RAM (NOLOAD) : + { + __dmaram_start__ = .; + *(.DMA_RAM) + . = ALIGN(32); + __dmaram_end__ = .; + } >FASTRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/system_at32f435_437.c b/src/main/target/system_at32f435_437.c new file mode 100644 index 0000000000..259d511fb1 --- /dev/null +++ b/src/main/target/system_at32f435_437.c @@ -0,0 +1,186 @@ +/** + ************************************************************************** + * @file system_at32f435_437.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for cmsis cortex-m4 system source file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +#include "at32f435_437.h" +#include "drivers/system.h" +#include "platform.h" +#include "drivers/persistent.h" + +/** @addtogroup AT32F435_437_system_private_defines + * @{ + */ +#define VECT_TAB_OFFSET 0x0 /*!< vector table base offset field. this value must be a multiple of 0x200. */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_variables + * @{ + */ +unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequency (core clock) */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_functions + * @{ + */ + +/** + * @brief setup the microcontroller system + * initialize the flash interface. + * @note this function should be used only after reset. + * @param none + * @retval none + */ +void SystemInit (void) +{ + initialiseMemorySections(); +#if defined (__FPU_USED) && (__FPU_USED == 1U) + SCB->CPACR |= ((3U << 10U * 2U) | /* set cp10 full access */ + (3U << 11U * 2U) ); /* set cp11 full access */ +#endif + + /* reset the crm clock configuration to the default reset state(for debug purpose) */ + /* set hicken bit */ + CRM->ctrl_bit.hicken = TRUE; + + /* wait hick stable */ + while(CRM->ctrl_bit.hickstbl != SET); + + /* hick used as system clock */ + CRM->cfg_bit.sclksel = CRM_SCLK_HICK; + + /* wait sclk switch status */ + while(CRM->cfg_bit.sclksts != CRM_SCLK_HICK); + + /* reset hexten, hextbyps, cfden and pllen bits */ + CRM->ctrl &= ~(0x010D0000U); + + /* reset cfg register, include sclk switch, ahbdiv, apb1div, apb2div, adcdiv, clkout bits */ + CRM->cfg = 0; + + /* reset pllms pllns pllfr pllrcs bits */ + CRM->pllcfg = 0x00033002U; + + /* reset clkout[3], usbbufs, hickdiv, clkoutdiv */ + CRM->misc1 = 0; + + /* disable all interrupts enable and clear pending bits */ + CRM->clkint = 0x009F0000U; +// todo set RAM +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal sram. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal flash. */ +#endif +} + +/** + * @brief update system_core_clock variable according to clock register values. + * the system_core_clock variable contains the core clock (hclk), it can + * be used by the user application to setup the systick timer or configure + * other parameters. + * @param none + * @retval none + */ +void system_core_clock_update(void) +{ + uint32_t pll_ns = 0, pll_ms = 0, pll_fr = 0, pll_clock_source = 0, pllrcsfreq = 0; + uint32_t temp = 0, div_value = 0; + crm_sclk_type sclk_source; + + static const uint8_t sys_ahb_div_table[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + static const uint8_t pll_fr_table[6] = {1, 2, 4, 8, 16, 32}; + + /* get sclk source */ + sclk_source = crm_sysclk_switch_status_get(); + + switch(sclk_source) + { + case CRM_SCLK_HICK: + if(((CRM->misc1_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) + system_core_clock = HICK_VALUE * 6; + else + system_core_clock = HICK_VALUE; + break; + case CRM_SCLK_HEXT: + system_core_clock = HEXT_VALUE; + break; + case CRM_SCLK_PLL: + /* get pll clock source */ + pll_clock_source = CRM->pllcfg_bit.pllrcs; + + /* get multiplication factor */ + pll_ns = CRM->pllcfg_bit.pllns; + pll_ms = CRM->pllcfg_bit.pllms; + pll_fr = pll_fr_table[CRM->pllcfg_bit.pllfr]; + + if (pll_clock_source == CRM_PLL_SOURCE_HICK) + { + /* hick selected as pll clock entry */ + pllrcsfreq = HICK_VALUE; + } + else + { + /* hext selected as pll clock entry */ + pllrcsfreq = HEXT_VALUE; + } + + system_core_clock = (uint32_t)(((uint64_t)pllrcsfreq * pll_ns) / (pll_ms * pll_fr)); + break; + default: + system_core_clock = HICK_VALUE; + break; + } + + /* compute sclk, ahbclk frequency */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sys_ahb_div_table[temp]; + /* ahbclk frequency */ + system_core_clock = system_core_clock >> div_value; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/src/main/target/system_at32f435_437.h b/src/main/target/system_at32f435_437.h new file mode 100644 index 0000000000..8bef4dbd98 --- /dev/null +++ b/src/main/target/system_at32f435_437.h @@ -0,0 +1,77 @@ +/** + ************************************************************************** + * @file system_at32f435_437.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief cmsis cortex-m4 system header file. + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __SYSTEM_AT32F435_437_H +#define __SYSTEM_AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +#define SystemCoreClock system_core_clock + +/** @defgroup AT32F435_437_system_exported_variables + * @{ + */ +extern unsigned int system_core_clock; /*!< system clock frequency (core clock) */ + +/** + * @} + */ + +/** @defgroup AT32F435_437_system_exported_functions + * @{ + */ + +extern void SystemInit(void); +extern void system_core_clock_update(void); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif +